From 73d467ab4da1d001c15a7ed364b3c6d30d9d9011 Mon Sep 17 00:00:00 2001 From: countryBumpkin Date: Mon, 28 Mar 2022 22:24:49 -0700 Subject: [PATCH] initial commit with base code --- .clang_complete | 41 + .gcc-flags.json | 8 + .gitignore | 5 + .vscode/extensions.json | 10 + cap_file.txt | Bin 0 -> 28118 bytes disable/IMU.cpp | 318 + include/IMU.cpp | 222 + include/README | 39 + include/comm.h | 125 + include/commandFunctions.h | 18 + include/sensors.h | 18 + include/supportFunctions.h | 24 + include/supportFunctions.h.gch | Bin 0 -> 15726 bytes include/validation_tests.h | 14 + lib/CRC/.arduino-ci.yml | 13 + lib/CRC/.github/workflows/arduino-lint.yml | 13 + .../.github/workflows/arduino_test_runner.yml | 17 + lib/CRC/.github/workflows/jsoncheck.yml | 18 + lib/CRC/CRC.h | 226 + lib/CRC/CRC12.cpp | 109 + lib/CRC/CRC12.h | 61 + lib/CRC/CRC16.cpp | 108 + lib/CRC/CRC16.h | 60 + lib/CRC/CRC32.cpp | 109 + lib/CRC/CRC32.h | 60 + lib/CRC/CRC64.cpp | 110 + lib/CRC/CRC64.h | 60 + lib/CRC/CRC8.cpp | 97 + lib/CRC/CRC8.h | 59 + lib/CRC/LICENSE | 21 + lib/CRC/README.md | 162 + lib/CRC/examples/CRC12_test/CRC12_test.ino | 102 + lib/CRC/examples/CRC16_test/CRC16_test.ino | 67 + .../CRC32_performance/CRC32_performance.ino | 81 + .../CRC32_performance/performance_0.2.0.txt | 13 + lib/CRC/examples/CRC32_test/CRC32_test.ino | 62 + lib/CRC/examples/CRC64_test/CRC64_test.ino | 63 + lib/CRC/examples/CRC8_test/CRC8_test.ino | 66 + .../CRC_performance/CRC_performance.ino | 118 + .../CRC_reference_test/CRC_reference_test.ino | 97 + lib/CRC/examples/CRC_test/CRC_test.ino | 46 + lib/CRC/keywords.txt | 42 + lib/CRC/library.json | 23 + lib/CRC/library.properties | 11 + lib/CRC/releaseNotes.md | 22 + lib/CRC/test/unit_test_001.cpp | 120 + lib/CRC/test/unit_test_crc12.cpp | 94 + lib/CRC/test/unit_test_crc16.cpp | 309 + lib/CRC/test/unit_test_crc32.cpp | 185 + lib/CRC/test/unit_test_crc64.cpp | 89 + lib/CRC/test/unit_test_crc8.cpp | 155 + lib/DRV10970/src/DRV_10970.cpp | 90 + lib/DRV10970/src/DRV_10970.h | 35 + lib/FreeRTOS-SAMD51/README.md | 43 + .../Basic_RTOS_Example/Basic_RTOS_Example.ino | 232 + .../Basic_RTOS_Example2.ino | 261 + .../CompilerAndLinker_Test.ino | 28 + .../CompilerAndLinker_Test/GameData.cpp | 2 + .../CompilerAndLinker_Test/GameData.h | 11 + .../CompilerAndLinker_Test/GameMessage.cpp | 4 + .../CompilerAndLinker_Test/GameMessage.h | 13 + .../CompilerAndLinker_Test/GameThing.c | 1 + .../CompilerAndLinker_Test/GameThing.h | 10 + .../GpioInterrupt_Test/GpioInterrupt_Test.ino | 278 + .../RtosCrash_Test/RtosCrash_Test.ino | 331 ++ .../TaskLoad_RTOS_Example.ino | 270 + lib/FreeRTOS-SAMD51/library.properties | 10 + lib/FreeRTOS-SAMD51/src/FreeRTOS.h | 1281 ++++ lib/FreeRTOS-SAMD51/src/FreeRTOSConfig.h | 177 + lib/FreeRTOS-SAMD51/src/FreeRTOS_SAMD51.h | 34 + lib/FreeRTOS-SAMD51/src/croutine.c | 353 ++ lib/FreeRTOS-SAMD51/src/croutine.h | 720 +++ .../src/deprecated_definitions.h | 279 + lib/FreeRTOS-SAMD51/src/error_hooks.cpp | 191 + lib/FreeRTOS-SAMD51/src/error_hooks.h | 63 + lib/FreeRTOS-SAMD51/src/event_groups.c | 753 +++ lib/FreeRTOS-SAMD51/src/event_groups.h | 757 +++ lib/FreeRTOS-SAMD51/src/heap_4bis.c | 605 ++ lib/FreeRTOS-SAMD51/src/idle_hook.c | 12 + lib/FreeRTOS-SAMD51/src/list.c | 198 + lib/FreeRTOS-SAMD51/src/list.h | 412 ++ lib/FreeRTOS-SAMD51/src/message_buffer.h | 799 +++ lib/FreeRTOS-SAMD51/src/mpu_prototypes.h | 157 + lib/FreeRTOS-SAMD51/src/mpu_wrappers.h | 186 + lib/FreeRTOS-SAMD51/src/port.c | 805 +++ lib/FreeRTOS-SAMD51/src/portable.h | 183 + lib/FreeRTOS-SAMD51/src/portmacro.h | 244 + lib/FreeRTOS-SAMD51/src/projdefs.h | 124 + lib/FreeRTOS-SAMD51/src/queue.c | 2941 +++++++++ lib/FreeRTOS-SAMD51/src/queue.h | 1655 ++++++ lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.c | 20 + lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.h | 24 + lib/FreeRTOS-SAMD51/src/semphr.h | 1140 ++++ lib/FreeRTOS-SAMD51/src/stack_macros.h | 129 + lib/FreeRTOS-SAMD51/src/stdint.readme | 27 + lib/FreeRTOS-SAMD51/src/stream_buffer.c | 1263 ++++ lib/FreeRTOS-SAMD51/src/stream_buffer.h | 855 +++ lib/FreeRTOS-SAMD51/src/task.h | 2431 ++++++++ lib/FreeRTOS-SAMD51/src/tasks.c | 5236 +++++++++++++++++ lib/FreeRTOS-SAMD51/src/timers.c | 1102 ++++ lib/FreeRTOS-SAMD51/src/timers.h | 1295 ++++ .../platform.local.txt | 49 + lib/ICM-20948/.gitattributes | 2 + lib/ICM-20948/.gitignore | 2 + lib/ICM-20948/CONTRIBUTING.md | 20 + lib/ICM-20948/DMP.md | 2436 ++++++++ lib/ICM-20948/ISSUE_TEMPLATE.md | 18 + lib/ICM-20948/License.md | 55 + lib/ICM-20948/README.md | 39 + .../Example10_DMP_FastMultipleSensors.ino | 491 ++ .../Example1_Basics/Example1_Basics.ino | 250 + .../Example2_Advanced/Example2_Advanced.ino | 332 ++ .../Example3_Interrupts.ino | 416 ++ .../Example4_WakeOnMotion.ino | 413 ++ .../Example5_DualSPITest.ino | 246 + .../Example6_DMP_Quat9_Orientation.ino | 245 + .../Example7_DMP_Quat6_EulerAngles.ino | 274 + .../Example8_DMP_RawAccel.ino | 196 + .../Example9_DMP_MultipleSensors.ino | 255 + .../Example999_Portable.ino | 339 ++ lib/ICM-20948/img/Contributing.JPG | Bin 0 -> 58028 bytes lib/ICM-20948/keywords.txt | 193 + lib/ICM-20948/library.properties | 9 + lib/ICM-20948/src/ICM_20948.cpp | 1806 ++++++ lib/ICM-20948/src/ICM_20948.h | 264 + lib/ICM-20948/src/util/AK09916_ENUMERATIONS.h | 15 + lib/ICM-20948/src/util/AK09916_REGISTERS.h | 83 + .../icm20948_img.dmp3a.h_14290 | 951 +++ lib/ICM-20948/src/util/ICM_20948_C.c | 2543 ++++++++ lib/ICM-20948/src/util/ICM_20948_C.h | 303 + lib/ICM-20948/src/util/ICM_20948_DMP.h | 695 +++ .../src/util/ICM_20948_ENUMERATIONS.h | 263 + lib/ICM-20948/src/util/ICM_20948_REGISTERS.h | 810 +++ .../icm20948_img.dmp3a.h_14301 | 951 +++ lib/ICM-20948/src/util/icm20948_img.dmp3a.h | 951 +++ lib/INA209/INA209.cpp | 246 + lib/INA209/INA209.h | 77 + .../INA209_read_write_registers.ino | 161 + lib/INA209/keywords.txt | 42 + lib/README | 46 + lib/commandFunctions/commandFunctions.cpp | 95 + lib/testFun/README.md | 2 + lib/testFun/test.cpp | 228 + lib/testFun/test.h | 4 + platformio.ini | 16 + src/comm.cpp | 152 + src/commandFunctions.cpp | 114 + src/main.cpp | 394 ++ src/sensors.cpp | 247 + src/supportFunctions.cpp | 63 + src/validation_tests.cpp | 31 + test/README | 11 + test/test_motor/README.md | 2 + test/test_motor/test.cpp | 48 + 154 files changed, 49874 insertions(+) create mode 100644 .clang_complete create mode 100644 .gcc-flags.json create mode 100644 .gitignore create mode 100644 .vscode/extensions.json create mode 100644 cap_file.txt create mode 100644 disable/IMU.cpp create mode 100644 include/IMU.cpp create mode 100644 include/README create mode 100644 include/comm.h create mode 100644 include/commandFunctions.h create mode 100644 include/sensors.h create mode 100644 include/supportFunctions.h create mode 100644 include/supportFunctions.h.gch create mode 100644 include/validation_tests.h create mode 100644 lib/CRC/.arduino-ci.yml create mode 100644 lib/CRC/.github/workflows/arduino-lint.yml create mode 100644 lib/CRC/.github/workflows/arduino_test_runner.yml create mode 100644 lib/CRC/.github/workflows/jsoncheck.yml create mode 100644 lib/CRC/CRC.h create mode 100644 lib/CRC/CRC12.cpp create mode 100644 lib/CRC/CRC12.h create mode 100644 lib/CRC/CRC16.cpp create mode 100644 lib/CRC/CRC16.h create mode 100644 lib/CRC/CRC32.cpp create mode 100644 lib/CRC/CRC32.h create mode 100644 lib/CRC/CRC64.cpp create mode 100644 lib/CRC/CRC64.h create mode 100644 lib/CRC/CRC8.cpp create mode 100644 lib/CRC/CRC8.h create mode 100644 lib/CRC/LICENSE create mode 100644 lib/CRC/README.md create mode 100644 lib/CRC/examples/CRC12_test/CRC12_test.ino create mode 100644 lib/CRC/examples/CRC16_test/CRC16_test.ino create mode 100644 lib/CRC/examples/CRC32_performance/CRC32_performance.ino create mode 100644 lib/CRC/examples/CRC32_performance/performance_0.2.0.txt create mode 100644 lib/CRC/examples/CRC32_test/CRC32_test.ino create mode 100644 lib/CRC/examples/CRC64_test/CRC64_test.ino create mode 100644 lib/CRC/examples/CRC8_test/CRC8_test.ino create mode 100644 lib/CRC/examples/CRC_performance/CRC_performance.ino create mode 100644 lib/CRC/examples/CRC_reference_test/CRC_reference_test.ino create mode 100644 lib/CRC/examples/CRC_test/CRC_test.ino create mode 100644 lib/CRC/keywords.txt create mode 100644 lib/CRC/library.json create mode 100644 lib/CRC/library.properties create mode 100644 lib/CRC/releaseNotes.md create mode 100644 lib/CRC/test/unit_test_001.cpp create mode 100644 lib/CRC/test/unit_test_crc12.cpp create mode 100644 lib/CRC/test/unit_test_crc16.cpp create mode 100644 lib/CRC/test/unit_test_crc32.cpp create mode 100644 lib/CRC/test/unit_test_crc64.cpp create mode 100644 lib/CRC/test/unit_test_crc8.cpp create mode 100644 lib/DRV10970/src/DRV_10970.cpp create mode 100644 lib/DRV10970/src/DRV_10970.h create mode 100644 lib/FreeRTOS-SAMD51/README.md create mode 100644 lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example/Basic_RTOS_Example.ino create mode 100644 lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example2/Basic_RTOS_Example2.ino create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/CompilerAndLinker_Test.ino create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.cpp create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.h create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.cpp create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.h create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.c create mode 100644 lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.h create mode 100644 lib/FreeRTOS-SAMD51/examples/GpioInterrupt_Test/GpioInterrupt_Test.ino create mode 100644 lib/FreeRTOS-SAMD51/examples/RtosCrash_Test/RtosCrash_Test.ino create mode 100644 lib/FreeRTOS-SAMD51/examples/TaskLoad_RTOS_Example/TaskLoad_RTOS_Example.ino create mode 100644 lib/FreeRTOS-SAMD51/library.properties create mode 100644 lib/FreeRTOS-SAMD51/src/FreeRTOS.h create mode 100644 lib/FreeRTOS-SAMD51/src/FreeRTOSConfig.h create mode 100644 lib/FreeRTOS-SAMD51/src/FreeRTOS_SAMD51.h create mode 100644 lib/FreeRTOS-SAMD51/src/croutine.c create mode 100644 lib/FreeRTOS-SAMD51/src/croutine.h create mode 100644 lib/FreeRTOS-SAMD51/src/deprecated_definitions.h create mode 100644 lib/FreeRTOS-SAMD51/src/error_hooks.cpp create mode 100644 lib/FreeRTOS-SAMD51/src/error_hooks.h create mode 100644 lib/FreeRTOS-SAMD51/src/event_groups.c create mode 100644 lib/FreeRTOS-SAMD51/src/event_groups.h create mode 100644 lib/FreeRTOS-SAMD51/src/heap_4bis.c create mode 100644 lib/FreeRTOS-SAMD51/src/idle_hook.c create mode 100644 lib/FreeRTOS-SAMD51/src/list.c create mode 100644 lib/FreeRTOS-SAMD51/src/list.h create mode 100644 lib/FreeRTOS-SAMD51/src/message_buffer.h create mode 100644 lib/FreeRTOS-SAMD51/src/mpu_prototypes.h create mode 100644 lib/FreeRTOS-SAMD51/src/mpu_wrappers.h create mode 100644 lib/FreeRTOS-SAMD51/src/port.c create mode 100644 lib/FreeRTOS-SAMD51/src/portable.h create mode 100644 lib/FreeRTOS-SAMD51/src/portmacro.h create mode 100644 lib/FreeRTOS-SAMD51/src/projdefs.h create mode 100644 lib/FreeRTOS-SAMD51/src/queue.c create mode 100644 lib/FreeRTOS-SAMD51/src/queue.h create mode 100644 lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.c create mode 100644 lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.h create mode 100644 lib/FreeRTOS-SAMD51/src/semphr.h create mode 100644 lib/FreeRTOS-SAMD51/src/stack_macros.h create mode 100644 lib/FreeRTOS-SAMD51/src/stdint.readme create mode 100644 lib/FreeRTOS-SAMD51/src/stream_buffer.c create mode 100644 lib/FreeRTOS-SAMD51/src/stream_buffer.h create mode 100644 lib/FreeRTOS-SAMD51/src/task.h create mode 100644 lib/FreeRTOS-SAMD51/src/tasks.c create mode 100644 lib/FreeRTOS-SAMD51/src/timers.c create mode 100644 lib/FreeRTOS-SAMD51/src/timers.h create mode 100644 lib/FreeRTOS-SAMD51/wrapping memory functions/platform.local.txt create mode 100644 lib/ICM-20948/.gitattributes create mode 100644 lib/ICM-20948/.gitignore create mode 100644 lib/ICM-20948/CONTRIBUTING.md create mode 100644 lib/ICM-20948/DMP.md create mode 100644 lib/ICM-20948/ISSUE_TEMPLATE.md create mode 100644 lib/ICM-20948/License.md create mode 100644 lib/ICM-20948/README.md create mode 100644 lib/ICM-20948/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example1_Basics/Example1_Basics.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example2_Advanced/Example2_Advanced.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example3_Interrupts/Example3_Interrupts.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example4_WakeOnMotion/Example4_WakeOnMotion.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example5_DualSPITest/Example5_DualSPITest.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example6_DMP_Quat9_Orientation/Example6_DMP_Quat9_Orientation.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example7_DMP_Quat6_EulerAngles/Example7_DMP_Quat6_EulerAngles.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example8_DMP_RawAccel/Example8_DMP_RawAccel.ino create mode 100644 lib/ICM-20948/examples/Arduino/Example9_DMP_MultipleSensors/Example9_DMP_MultipleSensors.ino create mode 100644 lib/ICM-20948/examples/PortableC/Example999_Portable/Example999_Portable.ino create mode 100644 lib/ICM-20948/img/Contributing.JPG create mode 100644 lib/ICM-20948/keywords.txt create mode 100644 lib/ICM-20948/library.properties create mode 100644 lib/ICM-20948/src/ICM_20948.cpp create mode 100644 lib/ICM-20948/src/ICM_20948.h create mode 100644 lib/ICM-20948/src/util/AK09916_ENUMERATIONS.h create mode 100644 lib/ICM-20948/src/util/AK09916_REGISTERS.h create mode 100644 lib/ICM-20948/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 create mode 100644 lib/ICM-20948/src/util/ICM_20948_C.c create mode 100644 lib/ICM-20948/src/util/ICM_20948_C.h create mode 100644 lib/ICM-20948/src/util/ICM_20948_DMP.h create mode 100644 lib/ICM-20948/src/util/ICM_20948_ENUMERATIONS.h create mode 100644 lib/ICM-20948/src/util/ICM_20948_REGISTERS.h create mode 100644 lib/ICM-20948/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 create mode 100644 lib/ICM-20948/src/util/icm20948_img.dmp3a.h create mode 100644 lib/INA209/INA209.cpp create mode 100644 lib/INA209/INA209.h create mode 100644 lib/INA209/example/INA209_read_write_registers/INA209_read_write_registers.ino create mode 100644 lib/INA209/keywords.txt create mode 100644 lib/README create mode 100644 lib/commandFunctions/commandFunctions.cpp create mode 100644 lib/testFun/README.md create mode 100644 lib/testFun/test.cpp create mode 100644 lib/testFun/test.h create mode 100644 platformio.ini create mode 100644 src/comm.cpp create mode 100644 src/commandFunctions.cpp create mode 100644 src/main.cpp create mode 100644 src/sensors.cpp create mode 100644 src/supportFunctions.cpp create mode 100644 src/validation_tests.cpp create mode 100644 test/README create mode 100644 test/test_motor/README.md create mode 100644 test/test_motor/test.cpp diff --git a/.clang_complete b/.clang_complete new file mode 100644 index 0000000..066aa93 --- /dev/null +++ b/.clang_complete @@ -0,0 +1,41 @@ +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/include +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/src +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/CRC +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/INA209 +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/ICM-20948/src +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/Wire +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SPI +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/FreeRTOS-SAMD51/src +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/DRV10970/src +-IC:/Users/deepg/.platformio/packages/framework-cmsis/CMSIS/Include +-IC:/Users/deepg/.platformio/packages/framework-cmsis-atmel/CMSIS/Device/ATMEL +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/cores/arduino51 +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/variants/SparkFun_SAMD51_Thing_Plus +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/commandFunctions +-IC:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/testFun +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/HID +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/I2S/src +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/LilyMini_Guide/src +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SAMD_AnalogCorrection/src +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SDU/src +-IC:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/USBHost/src +-IC:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include/c++/7.2.1 +-IC:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include/c++/7.2.1/arm-none-eabi +-IC:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/lib/gcc/arm-none-eabi/7.2.1/include +-IC:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/lib/gcc/arm-none-eabi/7.2.1/include-fixed +-IC:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include +-IC:/Users/deepg/.platformio/packages/tool-unity +-DPLATFORMIO=50205 +-DARDUINO_SAMD51_THING_PLUS +-D__SAMD51J20A__ +-D__SAMD51__ +-D__FPU_PRESENT +-DARM_MATH_CM4 +-DARDUINO=10805 +-DF_CPU=120000000L +-DUSBCON +-DUSB_VID=0x1B4F +-DUSB_PID=0xF016 +-DUSB_PRODUCT="SparkFun SAMD51 Thing Plus" +-DUSB_MANUFACTURER="SparkFun" +-DARDUINO_ARCH_SAMD diff --git a/.gcc-flags.json b/.gcc-flags.json new file mode 100644 index 0000000..7f4c8cd --- /dev/null +++ b/.gcc-flags.json @@ -0,0 +1,8 @@ +{ + "execPath": "C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/bin/arm-none-eabi-g++.exe", + "gccDefaultCFlags": "-fsyntax-only -std=gnu11 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -Os -ffunction-sections -fdata-sections -Wall -mcpu=cortex-m4 -mthumb -nostdlib --param max-inline-insns-single=500 -DPLATFORMIO=50205 -DARDUINO_SAMD51_THING_PLUS -D__SAMD51J20A__ -D__SAMD51__ -D__FPU_PRESENT -DARM_MATH_CM4 -DARDUINO=10805 -DF_CPU=120000000L -DUSBCON -DUSB_VID=0x1B4F -DUSB_PID=0xF016 -DUSB_PRODUCT=\"SparkFun\\ SAMD51\\ Thing\\ Plus\" -DUSB_MANUFACTURER=\"SparkFun\" -DARDUINO_ARCH_SAMD", + "gccDefaultCppFlags": "-fsyntax-only -fno-rtti -fno-exceptions -std=gnu++11 -fno-threadsafe-statics -mfloat-abi=hard -mfpu=fpv4-sp-d16 -Os -ffunction-sections -fdata-sections -Wall -mcpu=cortex-m4 -mthumb -nostdlib --param max-inline-insns-single=500 -DPLATFORMIO=50205 -DARDUINO_SAMD51_THING_PLUS -D__SAMD51J20A__ -D__SAMD51__ -D__FPU_PRESENT -DARM_MATH_CM4 -DARDUINO=10805 -DF_CPU=120000000L -DUSBCON -DUSB_VID=0x1B4F -DUSB_PID=0xF016 -DUSB_PRODUCT=\"SparkFun\\ SAMD51\\ Thing\\ Plus\" -DUSB_MANUFACTURER=\"SparkFun\" -DARDUINO_ARCH_SAMD", + "gccErrorLimit": 15, + "gccIncludePaths": "C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/include,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/src,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/CRC,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/INA209,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/ICM-20948/src,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/Wire,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SPI,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/FreeRTOS-SAMD51/src,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/DRV10970/src,C:/Users/deepg/.platformio/packages/framework-cmsis/CMSIS/Include,C:/Users/deepg/.platformio/packages/framework-cmsis-atmel/CMSIS/Device/ATMEL,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/cores/arduino51,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/variants/SparkFun_SAMD51_Thing_Plus,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/commandFunctions,C:/Users/deepg/OneDrive/Documents/U_of_I/2021-22_UofI/CS480/ADCS/test_adcs/lib/testFun,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/HID,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/I2S/src,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/LilyMini_Guide/src,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SAMD_AnalogCorrection/src,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/SDU/src,C:/Users/deepg/.platformio/packages/framework-arduino-samd-sparkfun/libraries/USBHost/src,C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include/c++/7.2.1,C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include/c++/7.2.1/arm-none-eabi,C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/lib/gcc/arm-none-eabi/7.2.1/include,C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/lib/gcc/arm-none-eabi/7.2.1/include-fixed,C:/Users/deepg/.platformio/packages/toolchain-gccarmnoneeabi@1.70201.0/arm-none-eabi/include,C:/Users/deepg/.platformio/packages/tool-unity", + "gccSuppressWarnings": false +} diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..89cc49c --- /dev/null +++ b/.gitignore @@ -0,0 +1,5 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch diff --git a/.vscode/extensions.json b/.vscode/extensions.json new file mode 100644 index 0000000..080e70d --- /dev/null +++ b/.vscode/extensions.json @@ -0,0 +1,10 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ], + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" + ] +} diff --git a/cap_file.txt b/cap_file.txt new file mode 100644 index 0000000000000000000000000000000000000000..71802fdb48e3ff0a9cf4140bebe226c4235f4b7d GIT binary patch literal 28118 zcmeI4U2k1i8HD$3koXV2;)<3g{R|QpkOrtkKNL4e2%)NJlQbePTUejk)1iSW}db7TKk-|@|OSi-#3=|=V1B$@~`E~<-ziBe7`fk-yPn)_4V=4 z-!4bv^_R=zK0(KU~KiEdLq3Uk~r= z@%NqOyXF3~SNBHmyOBFSaUKlT-O;Vr->maJ9Nc@$_iJJj?=RO*R#?=>!<(}`URO0| zopU`Mqz9{adR@~!8pL@mU#$5r)>n0%b97$8qv8E>`Ng_BbALV_$+@Ol{qb1u+^gD^ zxf9=v*72BaUiELrpF3mxczJVVz8|lij#p0x>(M&j9GSE?&h7B?`A$#eaQS?k%&qbL zqvez3Ph+0LEq?Ik^a^Ax;50?pSe$yKd)!DZVc~t<7@85o8#-PlaVXW8uRSGTK>77 zv#9`Uq4<+zUGUsUiqB8ua(nr`g|rkWX+JUt5#aa*>#rfJA<<- zouky6EQc9tmv^lfn|HHtg{rHScCb2Jt2&*zNpM=%N5{43Gq0LSr?o}Lwdgay+s+n+ zebt;vwdUz){$^-Yjylg)=_0@#_wJImraL3 zs^;l1shUY@P10eKnwhNG>g&vOqssRuaQa_AWNDucld73it@&~^NoT(n3Dl03eG)pF zwC&w@L{e0{R{0mtld$Vt>^hy9dDJnpPv&l?LM|!P%&2D4X>HMQt@4@d=uFF_9lmBV z(~TAke5n#oss%BEP=F8C}9oOn~`y4k52^~$2-}}>_%rLEVj#6uq4wHRN zLSJWopHs<9bECV?a*?^xi57PzF7s!yXP;@fIer%V;rJQs>GKA=J2n#~XC&U1X7?G1_oVsiJ|m$g^ZFTy&NCAHWOJW> za*3+N^nkx#*E`+pM<{7OgGx+GwEm@pPY`~zDqc(BQitn^5rwB zdcSUNz1VrT_l~RK71F0>Mm3YFHSZkl_8rH}exJ`|X68|H`kKsix|MTWQk-^O`mRf# zdDTp+*1S5}>N`s7IDI~o9dc#TxmKdjWm0usljiAMq+6U!aHCwquG%r3zbpUMKRLHk z+23^^E1#KeG|#ntLgXroqpCGeNAq-;RL!Jn&6lG|b@uCS@1w4OGwC|$FsYhJr?r(G z$D!{C%uu_0`An8hd#Wt$m!nBHpAuY`zP9=fIUU_6Gua_m#_za3rAaDhQ_ZAm&C}65 z9VS&XNv+9_LqcD7$eQuzaQdt!J9#xss@|`=UyHLl0yESuUp|xDdq)Fx6)*HOx6QuWK|>MYsGYjC5P=|&wb`;M0V?Nj8e%HpVM z&6lG|bzE0{?W&`#>?on*WM&@i@HInbI!kTRAth_JoX!M}DuJWan#>NnPG^D}b+qg| zTKVbZiaQgppVX=6ecW$%cy)f8$xrd5PW_()pGbQB+f3YVs;KwmWxgMO?8&rUewztD zf7~Y(GacOsdv=$5Bql>5w(kAv05ibaItor?k#Z zNAs@bk}ltwrPC#+bY6)YRZhooH1*TjXqrx52a~E_Ubo0PBb_`uN7>4nt*pt}-hE}U zuUhkTG+z!gSvx}ZGt-S`W*&9S>}RGMb!=!2^sWn*+GfulM z327gTONyIGlWcK5N6`Gwt>vyU?Vw)6i@i?ebAR1j^qE)9B()~#Fqt)5S#R$$XDSvQ z)owmb(s8Ye%;=b$cUSG0+23`R$}2OSR;4+U_BF%2o0S~R(_zwS=CgJL=Vw|Tb=J>F3<7D{^bje%_5dn#nrqXz9%IwK-yL)ynqk z=2jln9qBlknMXT(&19w^oZaGqXlBfukMTuFU=T zx)O5wS~(r3`02jU6=bgFvy*9g^rs@bdGl)BsH0`y(XyYJZnT)&cgaj#=Cdegf9uk# I@>`sK0MLTdd;kCd literal 0 HcmV?d00001 diff --git a/disable/IMU.cpp b/disable/IMU.cpp new file mode 100644 index 0000000..28fe3cb --- /dev/null +++ b/disable/IMU.cpp @@ -0,0 +1,318 @@ +/**************************************************************** +* Based on the Sparkfun provided library for the ICM-20948. +* Modified by Garrett Wells for a CS senior capstone project. This file provides +* only the initialization and setup configuration stuff for the SAMD51. Use with +* different hardware may result in unexpected errors or lack of function. +* +* USING THIS FILE: +* To use the IMU... +* 1. Call initIMU(), should setup IMU using ICM_20848 library +* 2. Use library functions to get data (see ICM_20848.h in lib). Useful + functions below. + * getAGMT() reads from sensors and stores values in agmt struct + * accX(), accY(), accZ() read only acceleration + * magXYZ() read only magnetic values on an axis + * gyrXYZ() read only gyro values on axis + * temp() read only temperature + * sleep() put device into sleep, may take a bit to wake up + * lowPower() less time to wake than sleep?? +* 3. To print debug data to the serial port there are helper functions in this file. +* Make sure you setup Serial first. +***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20949_IMU +#include +#include "wiring_private.h" + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void configFSS(); +void configDLPF(); + +/* + Call this function before attempting to read from the IMU, sets up the + I2C interface for the SAMD51 +*/ +void initIMU() +{ + #ifdef USE_SPI + SPI_PORT.begin(); + #else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); + #endif + + bool initialized = false; + while (!initialized) + { + #ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); + #else + myICM.begin(WIRE_PORT, AD0_VAL); + #endif + + if (myICM.status != ICM_20948_Stat_Ok) + { + delay(500); + } + else + { + initialized = true; + } + } +} + +/* + * Sets the Full scale ranges (FSR) for the accelerometer and the gyroscope. + */ +void configFSS(){ + // Set full scale ranges for both acc and gyr + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + + myFSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + + myFSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + + myICM.setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); +} + +/* + * Select the digital low-pass filter to use with the gyroscope and the accelerometer to reduce noise. + */ +void configDLPF(){ + ICM_20948_dlpcfg_t myDLPcfg; // Similar to FSS, this uses a configuration structure for the desired sensors + myDLPcfg.a = acc_d473bw_n499bw; // (ICM_20948_ACCEL_CONFIG_DLPCFG_e) + // acc_d246bw_n265bw - means 3db bandwidth is 246 hz and nyquist bandwidth is 265 hz + // acc_d111bw4_n136bw + // acc_d50bw4_n68bw8 + // acc_d23bw9_n34bw4 + // acc_d11bw5_n17bw + // acc_d5bw7_n8bw3 - means 3 db bandwidth is 5.7 hz and nyquist bandwidth is 8.3 hz + // acc_d473bw_n499bw + + myDLPcfg.g = gyr_d361bw4_n376bw5; // (ICM_20948_GYRO_CONFIG_1_DLPCFG_e) + // gyr_d196bw6_n229bw8 + // gyr_d151bw8_n187bw6 + // gyr_d119bw5_n154bw3 + // gyr_d51bw2_n73bw3 + // gyr_d23bw9_n35bw9 + // gyr_d11bw6_n17bw8 + // gyr_d5bw7_n8bw9 + // gyr_d361bw4_n376bw5 + + myICM.setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg); + ICM_20948_Status_e accDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Acc, false); + ICM_20948_Status_e gyrDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Gyr, true); +} + +//////////////////////////////////////////////////////////////////////////////// +// Below here are some helper functions to print the data nicely! +//////////////////////////////////////////////////////////////////////////////// + +/** + * @brief + * This function has something to do with printing IMU data over USB to the + * serial monitor. Other than that, I have no idea what it does. It came as part + * of the IMU demo code, and printScaledAGMT, which is used to validate data + * transmissions, relies on this function. + * + * @param[in] val Signed value to print + * + * @return None + */ +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +/** + * @brief + * This function has something to do with printing IMU data over USB to the + * serial monitor. Other than that, I have no idea what it does. It came as part + * of the IMU demo code, and printScaledAGMT, which is used to validate data + * transmissions, relies on this function. + * + * @param[in] agmt An instance of the IMU data object + * + * @return None + */ +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +/** + * @brief + * This function has something to do with printing IMU data over USB to the + * serial monitor. Other than that, I have no idea what it does. It came as part + * of the IMU demo code, and printScaledAGMT, which is used to validate data + * transmissions, relies on this function. + * + * @param[in] val Value to print + * @param[in] leading Number of digits left of the decimal + * @param[in] decimals Number of digits right of the decimal + * + * @return None + */ +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +/** + * @brief + * Prints IMU data over USB to the serial monitor. Converts raw data to a form + * that is readable by humans. Came as part of the IMU demo code. + * + * @param[in] sensor Pointer to IMU object + * + * @return None + */ +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ + #else + void printScaledAGMT(ICM_20948_I2C *sensor) + { + #endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); + } diff --git a/include/IMU.cpp b/include/IMU.cpp new file mode 100644 index 0000000..b682c5d --- /dev/null +++ b/include/IMU.cpp @@ -0,0 +1,222 @@ +/**************************************************************** +* Based on the Sparkfun provided library for the ICM-20949. +* Modified by Garrett Wells for a CS senior capstone project. This file provides +* only the initialization and setup configuration stuff for the SAMD51. Use with +* different hardware may result in unexpected errors or lack of function. +* +* USING THIS FILE: +* To use the IMU... +* 1. Call initIMU(), should setup IMU using ICM_20848 library +* 2. Use library functions to get data (see ICM_20848.h in lib). Useful + functions below. + * getAGMT() reads from sensors and stores values in agmt struct + * accX(), accY(), accZ() read only acceleration + * magXYZ() read only magnetic values on an axis + * gyrXYZ() read only gyro values on axis + * temp() read only temperature + * sleep() put device into sleep, may take a bit to wake up + * lowPower() less time to wake than sleep?? +* 3. To print debug data to the serial port there are helper functions in this file. +* Make sure you setup Serial first. +***************************************************************/ +#include "ICM_20949.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20949_IMU +#include +#include "wiring_private.h" + +// Create a new wire interface +TwoWire myWire(&sercom2, 12, 14); + +#define SERIAL_PORT SerialUSB + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT myWire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +/* + Call this function before attempting to read from the IMU, sets up the + I2C interface for the SAMD51 +*/ +void initIMU() +{ + #ifdef USE_SPI + SPI_PORT.begin(); + #else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); + #endif + + bool initialized = false; + while (!initialized) + { + #ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); + #else + myICM.begin(WIRE_PORT, AD0_VAL); + #endif + + if (myICM.status != ICM_20948_Stat_Ok) + { + delay(500); + } + else + { + initialized = true; + } + } +} + +//////////////////////////////////////////////////////////////////////////////// +// Below here are some helper functions to print the data nicely! +//////////////////////////////////////////////////////////////////////////////// +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ + #else + void printScaledAGMT(ICM_20948_I2C *sensor) + { + #endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); + } diff --git a/include/README b/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/include/comm.h b/include/comm.h new file mode 100644 index 0000000..2e0be27 --- /dev/null +++ b/include/comm.h @@ -0,0 +1,125 @@ +#ifndef __COMM_H__ +#define __COMM_H__ + +#include "CRC16.h" +#include + +// create more descriptive names for serial interfaces +#define SERCOM_USB Serial +#define SERCOM_UART Serial1 +#define SERCOM_I2C Wire +#define AD0_VAL 0 + +// packet sizes in bytes +#define COMMAND_LEN 4 +#define PACKET_LEN 12 + +// command values +enum Command : uint8_t +{ + CMD_STANDBY = 0xc0, + CMD_TEST = 0xa0 +}; + +// data packet status codes +enum Status : uint8_t +{ + STATUS_OK = 0xaa, // "Heartbeat" + STATUS_HELLO = 0xaf, // Sent upon system init + STATUS_ADCS_ERROR = 0xf0, // Sent upon runtime error + STATUS_COMM_ERROR = 0x99 // Sent upon invalid communication +}; + +/** + * @brief + * Defines a fixed-point data type that is one byte wide. Five bits are reserved + * for the integer part and 3 bits are reserved for the fraction part. While in + * fixed-point form, the data cannot be read - it must be converted back to + * floating-point first. Functions that convert float to fixed and back are + * declared below. + */ +typedef int8_t fixed5_3_t; + +/** + * @brief + */ +class TEScommand +{ +private: + // Stores data from TES as a union of an array and integers + union + { + // Data can be accessed as a single array - used when receiving bytes + uint8_t _data[COMMAND_LEN]; + + struct + { + // Data can be accessed as fields - used to extract command + uint16_t _command; + uint16_t _crc; + }; + }; + + // Counts the number of bytes received to see if the packet is full + uint8_t _bytes_received; + + // Flag that indicates when the packet is full + bool _full; + +public: + /** + * + */ + TEScommand(); + + /** + * + */ + void addByte(uint8_t b); + bool isFull(); + uint8_t getCommand(); + bool checkCRC(); + void clear(); +}; + +class ADCSdata +{ +private: + union + { + // Data can be accessed as a single array - used to send via UART + uint8_t _data[PACKET_LEN]; + + struct + { + // Data can be accessed as fields - used to build packet + uint8_t _status; + fixed5_3_t _voltage; + int8_t _current; + uint8_t _speed; + int8_t _magX; + int8_t _magY; + int8_t _magZ; + fixed5_3_t _gyroX; + fixed5_3_t _gyroY; + fixed5_3_t _gyroZ; + uint16_t _crc; + }; + }; + +public: + ADCSdata(); + void setStatus(uint8_t s); + void setINAdata(float v, float i); + void setSpeed(float s); + void setIMUdata(float mx, float my, float mz, float gx, float gy, float gz); + void computeCRC(); + void clear(); + void send(); +}; + +// fixed/float conversions +fixed5_3_t floatToFixed(float f); +float fixedToFloat(fixed5_3_t fix); + +#endif \ No newline at end of file diff --git a/include/commandFunctions.h b/include/commandFunctions.h new file mode 100644 index 0000000..0020230 --- /dev/null +++ b/include/commandFunctions.h @@ -0,0 +1,18 @@ +#ifndef __COMMAND_FUNCTIONS_H__ +#define __COMMAND_FUNCTIONS_H__ + + +#include "comm.h" +#include "sensors.h" +#include "DRV_10970.h" +/* These are the main functionalies and/or processes, they rely on the support + * functions (located in supportFunctions.cpp) to properally execute */ + +//This tests the sensors and makes sure they are reading correctly +void testFun(); +//This function has the satellite do nothing until something is in UART +void standby(); +//This corrdinates the satellite's rotation +void orient(const char *direction); + +#endif \ No newline at end of file diff --git a/include/sensors.h b/include/sensors.h new file mode 100644 index 0000000..13ec7c0 --- /dev/null +++ b/include/sensors.h @@ -0,0 +1,18 @@ +#ifndef __SENSORS_H__ +#define __SENSORS_H__ + +#include "comm.h" +#include "ICM_20948.h" +#include "INA209.h" + +void readIMU(ADCSdata &data_packet); +void readINA(ADCSdata &data_packet); + +// "helper" functions from IMU demo code that print sensor data to serial +// monitor over USB +void printPaddedInt16b(int16_t val); +void printRawAGMT(ICM_20948_AGMT_t agmt); +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals); +void printScaledAGMT(ICM_20948_I2C *sensor); + +#endif \ No newline at end of file diff --git a/include/supportFunctions.h b/include/supportFunctions.h new file mode 100644 index 0000000..f1265ff --- /dev/null +++ b/include/supportFunctions.h @@ -0,0 +1,24 @@ +#ifndef __SUPPORT_FUNCTIONS_H__ +#define __SUPPORT_FUNCTIONS_H__ + +/* These are functions that support the main command functions in one way + * or another they are called upon in the commandFunctions.cpp file */ +/* I tried to make these as self-explanatory as possible by name + * but I also added little descriptions anyways -Kristie */ + +// descriptive names for mode values +#define MODE_STANDBY 0 +#define MODE_TEST 1 + +// #define TWO_IMUS + +//Parses cmd and calls appropriate function +void doCmd(char *cmd); +//Reads output of sensors and compiles it into the array +void getData(int *data); +//Sends array data to main satellite system +void sendToSystem(int *data); +//Runs motors for a certain number of rotations +void startRotation(int rotations); + +#endif \ No newline at end of file diff --git a/include/supportFunctions.h.gch b/include/supportFunctions.h.gch new file mode 100644 index 0000000000000000000000000000000000000000..ae4590a9c36be075691cd34651598299654f87a4 GIT binary patch literal 15726 zcmbVT*={3AcAai}yzl#Ny4p+0GZJ!RW^xRVn2&*WWqGqZM ze}Vz~(SZF0e)Nmq{R{pB1O5-6b8louWKz|mnrf&eF)|}=+|!k01g`GuJ;X4CT%V>!uH2PdvwGa!;iWJQ(#h}Rh2M~umgDn_7~H$@xb&4-(QYrMJM__jQpm&Jen-RD3{m5z>1yp;wZ)F&sR^#mP{u+3bSs~ zOX6;jM^Th#-5~3wc^0SLIKu}~(oOU7FwRF*h|Yg97?^P}Fx_s?45nunlj5=y{b4;U z3VHKpTfX5=HxJkE*4$tmB$F3-sJ+45EWW%bu))X8!}`spyzX4RU2VA%_X@L&|F)Qp z%xE(0FY*A-g(;`_IT?hSsGY&ftAox}=d;f`6Wa0@WNdKSpPA$F0KElxYF2fl zD*aV_s&<~s3$Mn*#VKE*g>|A=G=^^k8e++DzHA`cB9596iMj_g=C8{*74ooK?bcUj z_3%(`cT`6bhLb-25rVsefZ=ztjE~g_(bOJ`fA`XNBpX56%2l|H6cw@Y&BsAMtF`2}f98 ztxBgF7U$F1nFZqY-Q(-q@?~<=OM~}s0GWo{de#XCDBQLu-dLy z*8pwBT0(9a-1sG)(ftZfjX+b7xdNQUTm5Z0A;$IjIW%SkuwK93?5JOd3Q}!NTQ3je zAUmM)l{QA>^YMaS03V&6PrjsrI~Z+A4J0+B79CRxUB;S`0xPM5(i3kH@#oY2yh12! z>|U<7?6b%pVQz&8oqhX*)$LStUO`jO^U#d=FtXvl5|J!Ltrd9}LVJ#I@9;@0fmu4Suf5KjmYOLV6* z$G4=fUOhCCU@Y+vkt^?IahUYFaW{)%(gY%NltMFc5C^>szm?x&;F~mJW13tFR%?*) z5k8@Nppfeua|J8x%J=tMQ44}Ix1cU6LX77U1Ji&}&}jHo6armbg7`sbhP$3CnRC?h z8f%(LPd7JDQq=KuI`Lh!sHMO%jPeZgkQIs#V00}_@Z+A>KS4AhQd zrS=Hqag`T_DP_|@qe(}#$?S&HDoCpJ`*33$Xu_BlYXo@_`{kiAe$YScga@32Rugi7 z`+6x-2Oq0#ym)Xig{aIyTsR<=)Uw18y{49>8-FmWV5g0!LTxEj=vu2=N%FvcKdd~9 z>!`Mtb4t)ZE+*z;R*c3pCN*NoU-K*gqITUl{~W`$sp)qf5|4sBiNFF`l;quR06$2A zAWOPYjwC(p^^jVGQ{L^ z(_R8v6K_d-G;8R(Y(r3FjhvF~R1kdJ*iG1r;LUJlRnh+* zx553XW6epg4vWO9hAtJOjpa7^3gY6UIE}&p>>Gz6q(b?SM))s-U|9@}ccU~Q(SUqi zMB?t-)6-QI(TH%hzxR%M@~`NDOPaaP?(Mc*T|caDB!)1lX3%7a&B4;2VLHw82)1(b z_zrp2?hbX9U!qC&-Jnt;r$MFh5pvM5hu{+Cd6Z;H3ObGQB`?;ge|#?a3bPb}k?ym}YgKyAdPajeiI8uQnd>)dgT;}DR4t9byUatS$Wc0<6T(%A zhN)b1(~Vnkq_~fLRFHCU+sv@m9&E|J2UV(^^TUAV@pSIup4JLBjse#hgis4b#%Tm}XPVy89U^ff$5bT~MQH;b8 zl?oEW@>`H-A|YGBNM6{keuxBg3z@X0L2mx%SVvXKkj;{&CZphe<)lnN_^-ujZJ9Zb zbwsau0o5hUg;h0LfL|1Y<)ptDBXgSfM}yB-P0azt#nt`o;{(5x%VKG(sPJOz^2YrA zBhrqWb*Zq+U~bOc2s;wi!s4*k9eNRTSRfA>^pOg5!e$-QuJIJmn3*eE%4FjZ*@~+% zxmO+2bghcQarB*99(4l+dVG`wQI0N9%Bm*H^KLH>3G6Tj<`JJ#5GW9ykNgS-XkgCk z_!irWgd3TxZ3S zh1m*GsPj9kTeL(u-&ds*#&65_=H~WpCCx*6KS@*HWyI(okIfgwYz`*rgs9^i9!@m0 zJ)E!W>{z;y)FQK#q?S{7&BEcU{%jPP!Dwvy^RrIq5*D007+Tu-6a~Iry?cGVlCAcF zOq^2nRZ#&VM~e!Mv7$l+GGVxpkUhUMh^&FO)zv6U)xc^r+gpJ}{NDx^<|oLp;c_{? zu|=1opAbZGlp(uC?=e7vf+i#b%jZ~0;|64Ix!n=GvlpSxKmm>p1!jxcF37T85~07@ zi;yZ~nuN9Zpq5znerdEfD%I~tv^toJQiUp#b%(09LyqXIHo1U?5zQTiGd(9v8eNOV z{#XP$T6umN7f0`1nNeku$K#kOja5-Kla|MkBqmzpSPJAM z*djU-C{%_*&5DXyaWY1MH*;ks!K?4u1h}Fbl8n<)9f|zheviC$*=HZE#1R9fTm9)H z5mL8CJZ!(J7U{yu>E~0_8lzr6xgHRdZ?O_2mBx=rI`z-)d$- zNxZH=lu%P@M$uH;LLAaPSh9k7UWDOMbQHXx1zZUNaJrVoa?-(|mK$_vlt@>1*QMb} z(dr7Vbcy|Jm{KfJq*Nsc-os*KPBo))^dr4DFQ2LMJFmCoI_2amuPZ_+8V>J;cm$1v z+o;E7jk;+PCEvzig>sx{nO8XYv4=mV^MPX^#zK8ZaxvR&_o>tG)VbP*idxm@aIaSn zayp5FM$H^4r*!A4=-_fI2Y1*PTWDIb$Ec%V#W3Gi|BGXOSofUpo*IyDtAPshz^sly z;Fw`|IOGGmK|Kb$7+$zDuo%Zcu6(Tk3kRzrH6R%s>?fL7-d7P4&6ik4H|=s-mySNX zy~DwruSvEge-dBXn52Me)`}*bzWBK!mpb3>cIys02N~eVoYAISJiYTJ@|R+M<=h`S z^2x`~c9ve{LEme4Qw}kao-jydiG&2liI*rcq{QHP*IXLXXGP})3ObylO^O!{domHS z?Z%vjQR(3WH7R+gw9Pu@di`d-GY=&Xw{3}s(!MuwDPb`gk&kIlb!KTm&d+d!+CMSV z<>F$A_As8HJvBR_t(+}=r8(-OCT9Jiv=N~CSlWm$*pMsZJ{gIYhP0i&g+UE zSZ-s~wK_C$tPtUmCR)v&hfB|fEJ$85WFr7#zC31z#G_WxQg9^QP+P(AX`PSSCS|sI zM7~o=&`_KMNs!p$ze~o@piwg~R<4xkPr;v;lfS_8ZHB>gAM*MJ&F*JjjX)x+x+Y8B z!BSTDEI%rlDg#%td8bygwRV9%#5C%OmRUcb*8NU%{Yjl&Ik3`fQI6mJy!lD3bWDP^Avc06IKnNcWT^dv22Znd$9Vu4niInOV z-47y6Yn28rX8n`1J_>7OB+Sx^%f)#gJnVPo86(^(E?1uyCuTHP;%sFxEnGX$RJ*LR zk1*wtP0i0Xq09l+7w~b%ab%gafB0qAj3fgE^6S^F~)&K z59i7;dgWaZl+&!oPt~4dxkl7t@0JIFyop#PN?50@eT*~ew$$`g^rAY{HVoV72ck2H zqv>mdOB&aZG!|j6_hN2S7pV%*HZio9W13P>lq=63BQ$Lrjq7!kA>jtaa+q)~YX74s^oiS89 zFXeM@9udhmyAlsy-Q9m>N;EI*!@RD>3n|~kmpu}uDwUy?MfXZc*9lS#wM)G0fSXZP zD=r7c1(OzF&#AfUK2>;0JrhU_@@kPZX{N&1$(zzJ4Zb!vclKC6ZuXx6wKi`xETx@% zX}v%H_5n+BCU_lu>1oNu1^j2!UxFsji&w3-`?vAfegKyk$8%oKYt-62>~+*DWzjp- zMz`kS9qh~CN?u8KPO~lHP#N>x!5}!({@ED@mkDKsnN4li@w%hxeA%#=FusMx(oH2(>MelKN zh+3Fui@GQ$^?j%cq1AW2#^kuk)?p5cG=i>54OR!iJeUL@K5@SAbp%W`lAanSTgVv= zujwI&U(A-gXx0f`Cd;tvb&a0iJf`N=pyIha=&!rhENPqJc)fwcmwI^!7px@bTH8K!!YUEF7FAj%fM;+BB zbL b%1tyiKt`Ur0oE@eJl3-bc#cN;GJF1+SGXY$HGhOokZHR8j`|#mDoH@W7%DLUOb~6S&e3<}_UqiFckdx}4AWI7L+xVj~rI;PYo+R$v#0 zb-7XiMfLFZV_bb;nXCdGe~G)(8ZkfEZKi^BW$c#dtG1dZY|5ztnc!?6H@o$_(yX@I z)mIN_c;;Cc$z5}oPql)&AEG#s>-Iy_Uh}M(xZ~h-^-!PT$$=s-p;OOwB&(pJy`bmU zqYbVmNwk|)M1@u)!f4JNIiOl?9sRl#^8$aKgOK|~n*!VQlUrXeq<96Xg^y?akHe7b zp|VNgmh@Lkv6|*=Sk02n^Yca~aB6GjrDs@o)9^aV6m&>U)3WjW6?c(o3m;poJ=ebs|@iFMWdXrX4$==0+HW-woLy3|BNv+afp z&eWM8C}gVo*Pq^}iU3a%2hxBCvHz$}aaGrNQMW=hFl3Jmy^9)}3&ZO?zm$uZ&1hi% zn$x>pB7fXNa4S!>)yzNVq!rXpU>>?= zGkb_rGMggLyHh`DH(46t2Hddc!7kSzA2%22J#if2b$=@ttG+KMOzD&@MYoMW^8CM@ zd2(l3PkN`~Y*whh5J$~?v_=t+>sbRz!~qeR`E)rOfS%ZR(zi+8ye?J!ose`Fc!z!u S=D0$}TWXzTZ=|}r7XLr4*Cdqy literal 0 HcmV?d00001 diff --git a/include/validation_tests.h b/include/validation_tests.h new file mode 100644 index 0000000..9616e19 --- /dev/null +++ b/include/validation_tests.h @@ -0,0 +1,14 @@ +#ifndef VALIDATION_TEST_H +#define VALIDATION_TEST_H + +#include "DRV_10970.h" +#include "ICM_20948.h" +#include +#include + +extern DRV10970 flywhl; +extern ICM_20948_I2C IMU1; + +void basic_motion1(void* pvParameters); + +#endif diff --git a/lib/CRC/.arduino-ci.yml b/lib/CRC/.arduino-ci.yml new file mode 100644 index 0000000..377bf84 --- /dev/null +++ b/lib/CRC/.arduino-ci.yml @@ -0,0 +1,13 @@ +compile: + # Choosing to run compilation tests on 2 different Arduino platforms + platforms: + - uno + # - due + # - zero + # - leonardo + - m4 + - esp32 + # - esp8266 + # - mega2560 + libraries: + - "printHelpers" \ No newline at end of file diff --git a/lib/CRC/.github/workflows/arduino-lint.yml b/lib/CRC/.github/workflows/arduino-lint.yml new file mode 100644 index 0000000..b2ca058 --- /dev/null +++ b/lib/CRC/.github/workflows/arduino-lint.yml @@ -0,0 +1,13 @@ + +name: Arduino-lint + +on: [push, pull_request] +jobs: + lint: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - uses: arduino/arduino-lint-action@v1 + with: + library-manager: update + compliance: strict diff --git a/lib/CRC/.github/workflows/arduino_test_runner.yml b/lib/CRC/.github/workflows/arduino_test_runner.yml new file mode 100644 index 0000000..096b975 --- /dev/null +++ b/lib/CRC/.github/workflows/arduino_test_runner.yml @@ -0,0 +1,17 @@ +--- +name: Arduino CI + +on: [push, pull_request] + +jobs: + runTest: + runs-on: ubuntu-latest + + steps: + - uses: actions/checkout@v2 + - uses: ruby/setup-ruby@v1 + with: + ruby-version: 2.6 + - run: | + gem install arduino_ci + arduino_ci.rb diff --git a/lib/CRC/.github/workflows/jsoncheck.yml b/lib/CRC/.github/workflows/jsoncheck.yml new file mode 100644 index 0000000..04603d0 --- /dev/null +++ b/lib/CRC/.github/workflows/jsoncheck.yml @@ -0,0 +1,18 @@ +name: JSON check + +on: + push: + paths: + - '**.json' + pull_request: + +jobs: + test: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - name: json-syntax-check + uses: limitusus/json-syntax-check@v1 + with: + pattern: "\\.json$" + diff --git a/lib/CRC/CRC.h b/lib/CRC/CRC.h new file mode 100644 index 0000000..8723a5f --- /dev/null +++ b/lib/CRC/CRC.h @@ -0,0 +1,226 @@ +#pragma once +// +// FILE: CRC.h +// AUTHOR: Rob Tillaart +// VERSION: 0.2.0 +// PURPOSE: Arduino library fir CRC8, CRC12, CRC16, CRC16-CCITT, CRC32 +// URL: https://github.com/RobTillaart/CRC +// + + +#include "Arduino.h" + + +#define CRC_LIB_VERSION (F("0.2.0")) + + +//////////////////////////////////////////////////////////////// +// +// fast reverse from bitHelper library +// + +uint8_t reverse8(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +uint16_t reverse16(uint16_t in) +{ + uint16_t x = in; + x = (((x & 0XAAAA) >> 1) | ((x & 0X5555) << 1)); + x = (((x & 0xCCCC) >> 2) | ((x & 0X3333) << 2)); + x = (((x & 0xF0F0) >> 4) | ((x & 0X0F0F) << 4)); + x = (( x >> 8) | (x << 8)); + return x; +} + + +uint16_t reverse12(uint16_t in) +{ + return reverse16(in) >> 4; +} + + +uint32_t reverse32(uint32_t in) +{ + uint32_t x = in; + x = (((x & 0xAAAAAAAA) >> 1) | ((x & 0x55555555) << 1)); + x = (((x & 0xCCCCCCCC) >> 2) | ((x & 0x33333333) << 2)); + x = (((x & 0xF0F0F0F0) >> 4) | ((x & 0x0F0F0F0F) << 4)); + x = (((x & 0xFF00FF00) >> 8) | ((x & 0x00FF00FF) << 8)); + x = (x >> 16) | (x << 16); + return x; +} + + +uint64_t reverse64(uint64_t in) +{ + uint64_t x = in; + x = (((x & 0xAAAAAAAAAAAAAAAA) >> 1) | ((x & 0x5555555555555555) << 1)); + x = (((x & 0xCCCCCCCCCCCCCCCC) >> 2) | ((x & 0x3333333333333333) << 2)); + x = (((x & 0xF0F0F0F0F0F0F0F0) >> 4) | ((x & 0x0F0F0F0F0F0F0F0F) << 4)); + x = (((x & 0xFF00FF00FF00FF00) >> 8) | ((x & 0x00FF00FF00FF00FF) << 8)); + x = (((x & 0xFFFF0000FFFF0000) >> 16) | ((x & 0x0000FFFF0000FFFF) << 16)); + x = (x >> 32) | (x << 32); + return x; +} + + +/////////////////////////////////////////////////////////////////////////////////// + +// CRC POLYNOME = x8 + x5 + x4 + 1 = 1001 1000 = 0x8C +uint8_t crc8(const uint8_t *array, uint8_t length, const uint8_t polynome = 0xD5, const uint8_t startmask = 0x00, const uint8_t endmask = 0x00, const bool reverseIn = false, const bool reverseOut = false) +{ + uint8_t crc = startmask; + while (length--) + { + uint8_t data = *array++; + if (reverseIn) data = reverse8(data); + crc ^= data; + for (uint8_t i = 8; i; i--) + { + if (crc & 0x80) + { + crc <<= 1; + crc ^= polynome; + } + else + { + crc <<= 1; + } + } + } + crc ^= endmask; + if (reverseOut) crc = reverse8(crc); + return crc; +} + + +// CRC POLYNOME = x12 + x3 + x2 + 1 = 0000 1000 0000 1101 = 0x80D +uint16_t crc12(const uint8_t *array, uint8_t length, const uint16_t polynome = 0x80D, const uint16_t startmask = 0x0000, const uint16_t endmask = 0x0000, const bool reverseIn = false, const bool reverseOut = false) +{ + uint16_t crc = startmask; + while (length--) + { + uint8_t data = *array++; + if (reverseIn) data = reverse8(data); + + crc ^= ((uint16_t)data) << 4; + for (uint8_t i = 8; i; i--) + { + if (crc & (1 << 11) ) + { + crc <<= 1; + crc ^= polynome; + } + else + { + crc <<= 1; + } + } + } + + if (reverseOut) crc = reverse12(crc); + crc ^= endmask; + return crc; +} + + +// CRC POLYNOME = x15 + 1 = 1000 0000 0000 0001 = 0x8001 +uint16_t crc16(const uint8_t *array, uint8_t length, const uint16_t polynome = 0x8001, const uint16_t startmask = 0x0000, const uint16_t endmask = 0x0000, const bool reverseIn = false, const bool reverseOut = false) +{ + uint16_t crc = startmask; + while (length--) + { + uint8_t data = *array++; + if (reverseIn) data = reverse8(data); + crc ^= ((uint16_t)data) << 8; + for (uint8_t i = 8; i; i--) + { + if (crc & (1 << 15)) + { + crc <<= 1; + crc ^= polynome; + } + else + { + crc <<= 1; + } + } + } + if (reverseOut) crc = reverse16(crc); + crc ^= endmask; + return crc; +} + + +// CRC-CCITT POLYNOME = x13 + X5 + 1 = 0001 0000 0010 0001 = 0x1021 +uint16_t crc16_CCITT(uint8_t *array, uint8_t length) +{ + return crc16(array, length, 0x1021, 0xFFFF); +} + + +// CRC-32 POLYNOME = x32 + ..... + 1 +uint32_t crc32(const uint8_t *array, uint8_t length, const uint32_t polynome = 0x04C11DB7, const uint32_t startmask = 0, const uint32_t endmask = 0, const bool reverseIn = false, const bool reverseOut = false) +{ + uint32_t crc = startmask; + while (length--) + { + uint8_t data = *array++; + if (reverseIn) data = reverse8(data); + crc ^= ((uint32_t) data) << 24; + for (uint8_t i = 8; i; i--) + { + if (crc & (1UL << 31)) + { + crc <<= 1; + crc ^= polynome; + } + else + { + crc <<= 1; + } + } + } + crc ^= endmask; + if (reverseOut) crc = reverse32(crc); + return crc; +} + + +// CRC-CCITT POLYNOME = x64 + ..... + 1 +uint64_t crc64(const uint8_t *array, uint8_t length, const uint64_t polynome, const uint64_t startmask, const uint64_t endmask, const bool reverseIn, const bool reverseOut) +{ + uint64_t crc = startmask; + while (length--) + { + uint8_t data = *array++; + if (reverseIn) data = reverse8(data); + crc ^= ((uint64_t) data) << 56; + for (uint8_t i = 8; i; i--) + { + if (crc & (1ULL << 63)) + { + crc <<= 1; + crc ^= polynome; + } + else + { + crc <<= 1; + } + } + } + crc ^= endmask; + if (reverseOut) crc = reverse64(crc); + return crc; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC12.cpp b/lib/CRC/CRC12.cpp new file mode 100644 index 0000000..ca212e1 --- /dev/null +++ b/lib/CRC/CRC12.cpp @@ -0,0 +1,109 @@ +// +// FILE: CRC12.cpp +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC12 +// URL: https://github.com/RobTillaart/CRC + + +#include "CRC12.h" + + +CRC12::CRC12() +{ + reset(); +} + + +void CRC12::reset() +{ + _polynome = CRC12_DEFAULT_POLYNOME; + _startMask = 0; + _endMask = 0; + _crc = 0; + _reverseIn = false; + _reverseOut = false; + _started = false; + _count = 0; +} + + +void CRC12::restart() +{ + _started = true; + _crc = _startMask; + _count = 0; +} + + +void CRC12::add(uint8_t value) +{ + _count++; + _update(value); +} + + +void CRC12::add(const uint8_t * array, uint8_t length) +{ + _count += length; + while (length--) + { + // reduce yield() calls + if ((_count & 0xFF) == 0xFF) yield(); + _update(*array++); + } +} + + +uint16_t CRC12::getCRC() +{ + uint16_t rv = _crc; + if (_reverseOut) rv = _reverse(rv); + rv ^= _endMask; + return rv & 0x0FFF; +} + + +void CRC12::_update(uint8_t value) +{ + if (!_started) restart(); + if (_reverseIn) value = _reverse8(value); + _crc ^= ((uint16_t)value) << 4; + for (uint8_t i = 8; i; i--) + { + if (_crc & (1 << 11)) + { + _crc <<= 1; + _crc ^= _polynome; + } + else + { + _crc <<= 1; + } + } +} + + +uint16_t CRC12::_reverse(uint16_t in) +{ + // return reverse16(in) >> 4; + uint16_t x = in; + x = (((x & 0XAAAA) >> 1) | ((x & 0X5555) << 1)); + x = (((x & 0xCCCC) >> 2) | ((x & 0X3333) << 2)); + x = (((x & 0xF0F0) >> 4) | ((x & 0X0F0F) << 4)); + x = (( x >> 8) | (x << 8)); + return x >> 4; +} + + +uint8_t CRC12::_reverse8(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC12.h b/lib/CRC/CRC12.h new file mode 100644 index 0000000..0fad80a --- /dev/null +++ b/lib/CRC/CRC12.h @@ -0,0 +1,61 @@ +#pragma once +// +// FILE: CRC12.h +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC12 +// URL: https://github.com/RobTillaart/CRC +// https://github.com/RobTillaart/CRC/issues/13 + + +#include "Arduino.h" + +#define CRC12_DEFAULT_POLYNOME 0x080D + + +class CRC12 +{ +public: + CRC12(); + + // set parameters to default + void reset(); // set all to constructor defaults + void restart(); // reset CRC with same parameters. + + // set parameters + void setPolynome(uint16_t polynome) { _polynome = polynome; }; + void setStartXOR(uint16_t start) { _startMask = start; }; + void setEndXOR(uint16_t end) { _endMask = end; }; + void setReverseIn(bool reverseIn) { _reverseIn = reverseIn; }; + void setReverseOut(bool reverseOut) { _reverseOut = reverseOut; }; + + // get parameters + uint16_t getPolynome() { return _polynome; }; + uint16_t getStartXOR() { return _startMask; }; + uint16_t getEndXOR() { return _endMask; }; + bool getReverseIn() { return _reverseIn; }; + bool getReverseOut() { return _reverseOut; }; + + void add(uint8_t value); + void add(const uint8_t * array, uint8_t length); + + uint16_t getCRC(); // returns CRC + uint32_t count() { return _count; }; + +private: + uint16_t _reverse(uint16_t value); + uint8_t _reverse8(uint8_t value); + void _update(uint8_t value); + + uint16_t _polynome; + uint16_t _startMask; + uint16_t _endMask; + uint16_t _crc; + bool _reverseIn; + bool _reverseOut; + bool _started; + uint32_t _count; +}; + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC16.cpp b/lib/CRC/CRC16.cpp new file mode 100644 index 0000000..0d3d655 --- /dev/null +++ b/lib/CRC/CRC16.cpp @@ -0,0 +1,108 @@ +// +// FILE: CRC16.cpp +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC16 +// URL: https://github.com/RobTillaart/CRC + + +#include "CRC16.h" + + +CRC16::CRC16() +{ + reset(); +} + + +void CRC16::reset() +{ + _polynome = CRC16_DEFAULT_POLYNOME; + _startMask = 0; + _endMask = 0; + _crc = 0; + _reverseIn = false; + _reverseOut = false; + _started = false; + _count = 0; +} + + +void CRC16::restart() +{ + _started = true; + _crc = _startMask; + _count = 0; +} + + +void CRC16::add(uint8_t value) +{ + _count++; + _update(value); +} + + +void CRC16::add(const uint8_t * array, uint8_t length) +{ + _count += length; + while (length--) + { + // reduce yield() calls + if ((_count & 0xFF) == 0xFF) yield(); + _update(*array++); + } +} + + +uint16_t CRC16::getCRC() +{ + uint16_t rv = _crc; + if (_reverseOut) rv = _reverse(rv); + rv ^= _endMask; + return rv; +} + + +void CRC16::_update(uint8_t value) +{ + if (!_started) restart(); + if (_reverseIn) value = _reverse8(value); + _crc ^= ((uint16_t)value) << 8;; + for (uint8_t i = 8; i; i--) + { + if (_crc & (1UL << 15)) + { + _crc <<= 1; + _crc ^= _polynome; + } + else + { + _crc <<= 1; + } + } +} + + +uint16_t CRC16::_reverse(uint16_t in) +{ + uint16_t x = in; + x = (((x & 0XAAAA) >> 1) | ((x & 0X5555) << 1)); + x = (((x & 0xCCCC) >> 2) | ((x & 0X3333) << 2)); + x = (((x & 0xF0F0) >> 4) | ((x & 0X0F0F) << 4)); + x = (( x >> 8) | (x << 8)); + return x; +} + + +uint8_t CRC16::_reverse8(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC16.h b/lib/CRC/CRC16.h new file mode 100644 index 0000000..fea3ec8 --- /dev/null +++ b/lib/CRC/CRC16.h @@ -0,0 +1,60 @@ +#pragma once +// +// FILE: CRC16.h +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC16 +// URL: https://github.com/RobTillaart/CRC + + +#include "Arduino.h" + +#define CRC16_DEFAULT_POLYNOME 0x1021 + + +class CRC16 +{ +public: + CRC16(); + + // set parameters to default + void reset(); // set all to constructor defaults + void restart(); // reset crc with same parameters. + + // set parameters + void setPolynome(uint16_t polynome) { _polynome = polynome; }; + void setStartXOR(uint16_t start) { _startMask = start; }; + void setEndXOR(uint16_t end) { _endMask = end; }; + void setReverseIn(bool reverseIn) { _reverseIn = reverseIn; }; + void setReverseOut(bool reverseOut) { _reverseOut = reverseOut; }; + + // get parameters + uint16_t getPolynome() { return _polynome; }; + uint16_t getStartXOR() { return _startMask; }; + uint16_t getEndXOR() { return _endMask; }; + bool getReverseIn() { return _reverseIn; }; + bool getReverseOut() { return _reverseOut; }; + + void add(uint8_t value); + void add(const uint8_t * array, uint8_t length); + + uint16_t getCRC(); // returns CRC + uint32_t count() { return _count; }; + +private: + uint16_t _reverse(uint16_t value); + uint8_t _reverse8(uint8_t value); + void _update(uint8_t value); + + uint16_t _polynome; + uint16_t _startMask; + uint16_t _endMask; + uint16_t _crc; + bool _reverseIn; + bool _reverseOut; + bool _started; + uint32_t _count; +}; + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC32.cpp b/lib/CRC/CRC32.cpp new file mode 100644 index 0000000..7c85826 --- /dev/null +++ b/lib/CRC/CRC32.cpp @@ -0,0 +1,109 @@ +// +// FILE: CRC32.cpp +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC32; +// URL: https://github.com/RobTillaart/CRC + + +#include "CRC32.h" + + +CRC32::CRC32() +{ + reset(); +} + + +void CRC32::reset() +{ + _polynome = CRC32_DEFAULT_POLYNOME; + _startMask = 0; + _endMask = 0; + _crc = 0; + _reverseIn = false; + _reverseOut = false; + _started = false; + _count = 0; +} + + +void CRC32::restart() +{ + _started = true; + _crc = _startMask; + _count = 0; +} + + +void CRC32::add(uint8_t value) +{ + _count++; + _update(value); +} + + +void CRC32::add(const uint8_t * array, uint8_t length) +{ + _count += length; + while (length--) + { + // reduce yield() calls + if ((_count & 0xFF) == 0xFF) yield(); + _update(*array++); + } +} + + +uint32_t CRC32::getCRC() +{ + uint32_t rv = _crc; + if (_reverseOut) rv = _reverse(rv); + rv ^=_endMask; + return rv; +} + + +void CRC32::_update(uint8_t value) +{ + if (!_started) restart(); + if (_reverseIn) value = _reverse8(value); + _crc ^= ((uint32_t)value) << 24;; + for (uint8_t i = 8; i; i--) + { + if (_crc & (1UL << 31)) + { + _crc <<= 1; + _crc ^= _polynome; + } + else + { + _crc <<= 1; + } + } +} + + +uint32_t CRC32::_reverse(uint32_t in) +{ + uint32_t x = in; + x = (((x & 0xAAAAAAAA) >> 1) | ((x & 0x55555555) << 1)); + x = (((x & 0xCCCCCCCC) >> 2) | ((x & 0x33333333) << 2)); + x = (((x & 0xF0F0F0F0) >> 4) | ((x & 0x0F0F0F0F) << 4)); + x = (((x & 0xFF00FF00) >> 8) | ((x & 0x00FF00FF) << 8)); + x = (x >> 16) | (x << 16); + return x; +} + + +uint8_t CRC32::_reverse8(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC32.h b/lib/CRC/CRC32.h new file mode 100644 index 0000000..802ad0a --- /dev/null +++ b/lib/CRC/CRC32.h @@ -0,0 +1,60 @@ +#pragma once +// +// FILE: CRC32.h +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC32 +// URL: https://github.com/RobTillaart/CRC + + +#include "Arduino.h" + +#define CRC32_DEFAULT_POLYNOME 0x04C11DB7 + + +class CRC32 +{ +public: + CRC32(); + + // set parameters to default + void reset(); // set all to constructor defaults + void restart(); // reset crc with same parameters. + + // set parameters + void setPolynome(uint32_t polynome) { _polynome = polynome; }; + void setStartXOR(uint32_t start) { _startMask = start; }; + void setEndXOR(uint32_t end) { _endMask = end; }; + void setReverseIn(bool reverseIn) { _reverseIn = reverseIn; }; + void setReverseOut(bool reverseOut) { _reverseOut = reverseOut; }; + + // get parameters + uint32_t getPolynome() { return _polynome; }; + uint32_t getStartXOR() { return _startMask; }; + uint32_t getEndXOR() { return _endMask; }; + bool getReverseIn() { return _reverseIn; }; + bool getReverseOut() { return _reverseOut; }; + + void add(uint8_t value); + void add(const uint8_t * array, uint8_t length); + + uint32_t getCRC(); // returns CRC + uint32_t count() { return _count; }; + +private: + uint32_t _reverse(uint32_t value); + uint8_t _reverse8(uint8_t value); + void _update(uint8_t value); + + uint32_t _polynome; + uint32_t _startMask; + uint32_t _endMask; + uint32_t _crc; + bool _reverseIn; + bool _reverseOut; + bool _started; + uint32_t _count; +}; + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC64.cpp b/lib/CRC/CRC64.cpp new file mode 100644 index 0000000..850fb63 --- /dev/null +++ b/lib/CRC/CRC64.cpp @@ -0,0 +1,110 @@ +// +// FILE: CRC64.cpp +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC64; +// URL: https://github.com/RobTillaart/CRC + + +#include "CRC64.h" + + +CRC64::CRC64() +{ + reset(); +} + + +void CRC64::reset() +{ + _polynome = CRC64_DEFAULT_POLYNOME; + _startMask = 0; + _endMask = 0; + _crc = 0; + _reverseIn = false; + _reverseOut = false; + _started = false; + _count = 0; +} + + +void CRC64::restart() +{ + _started = true; + _crc = _startMask; + _count = 0; +} + + +void CRC64::add(uint8_t value) +{ + _count++; + _update(value); +} + + +void CRC64::add(const uint8_t * array, uint8_t length) +{ + _count += length; + while (length--) + { + // reduce yield() calls + if ((_count & 0xFF) == 0xFF) yield(); + _update(*array++); + } +} + + +uint64_t CRC64::getCRC() +{ + uint64_t rv = _crc; + if (_reverseOut) rv = _reverse(rv); + rv ^=_endMask; + return rv; +} + + +void CRC64::_update(uint8_t value) +{ + if (!_started) restart(); + if (_reverseIn) value = _reverse8(value); + _crc ^= ((uint64_t)value) << 56;; + for (uint8_t i = 8; i; i--) + { + if (_crc & (1ULL << 63)) + { + _crc <<= 1; + _crc ^= _polynome; + } + else + { + _crc <<= 1; + } + } +} + + +uint64_t CRC64::_reverse(uint64_t in) +{ + uint64_t x = in; + x = (((x & 0xAAAAAAAAAAAAAAAA) >> 1) | ((x & 0x5555555555555555) << 1)); + x = (((x & 0xCCCCCCCCCCCCCCCC) >> 2) | ((x & 0x3333333333333333) << 2)); + x = (((x & 0xF0F0F0F0F0F0F0F0) >> 4) | ((x & 0x0F0F0F0F0F0F0F0F) << 4)); + x = (((x & 0xFF00FF00FF00FF00) >> 8) | ((x & 0x00FF00FF00FF00FF) << 8)); + x = (((x & 0xFFFF0000FFFF0000) >> 16) | ((x & 0x0000FFFF0000FFFF) << 16)); + x = (x >> 32) | (x << 32); + return x; +} + + +uint8_t CRC64::_reverse8(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC64.h b/lib/CRC/CRC64.h new file mode 100644 index 0000000..5083abd --- /dev/null +++ b/lib/CRC/CRC64.h @@ -0,0 +1,60 @@ +#pragma once +// +// FILE: CRC64.h +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC64 +// URL: https://github.com/RobTillaart/CRC + + +#include "Arduino.h" + +#define CRC64_DEFAULT_POLYNOME 0x814141AB + + +class CRC64 +{ +public: + CRC64(); + + // set parameters to default + void reset(); // set all to constructor defaults + void restart(); // reset crc with same parameters. + + // set parameters + void setPolynome(uint64_t polynome) { _polynome = polynome; }; + void setStartXOR(uint64_t start) { _startMask = start; }; + void setEndXOR(uint64_t end) { _endMask = end; }; + void setReverseIn(bool reverseIn) { _reverseIn = reverseIn; }; + void setReverseOut(bool reverseOut) { _reverseOut = reverseOut; }; + + // get parameters + uint64_t getPolynome() { return _polynome; }; + uint64_t getStartXOR() { return _startMask; }; + uint64_t getEndXOR() { return _endMask; }; + bool getReverseIn() { return _reverseIn; }; + bool getReverseOut() { return _reverseOut; }; + + void add(uint8_t value); + void add(const uint8_t * array, uint8_t length); + + uint64_t getCRC(); // returns CRC + uint64_t count() { return _count; }; + +private: + uint64_t _reverse(uint64_t value); + uint8_t _reverse8(uint8_t value); + void _update(uint8_t value); + + uint64_t _polynome; + uint64_t _startMask; + uint64_t _endMask; + uint64_t _crc; + bool _reverseIn; + bool _reverseOut; + bool _started; + uint64_t _count; +}; + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC8.cpp b/lib/CRC/CRC8.cpp new file mode 100644 index 0000000..7c5f34f --- /dev/null +++ b/lib/CRC/CRC8.cpp @@ -0,0 +1,97 @@ +// +// FILE: CRC8.cpp +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC8; +// URL: https://github.com/RobTillaart/CRC + + +#include "CRC8.h" + + +CRC8::CRC8() +{ + reset(); +} + + +void CRC8::reset() +{ + _polynome = CRC8_DEFAULT_POLYNOME; + _startMask = 0; + _endMask = 0; + _crc = 0; + _reverseIn = false; + _reverseOut = false; + _started = false; + _count = 0; +} + + +void CRC8::restart() +{ + _started = true; + _crc = _startMask; + _count = 0; +} + + +void CRC8::add(uint8_t value) +{ + _count++; + _update(value); +} + + +void CRC8::add(const uint8_t * array, uint8_t length) +{ + _count += length; + while (length--) + { + // reduce yield() calls + if ((_count & 0xFF) == 0xFF) yield(); + _update(*array++); + } +} + + +uint8_t CRC8::getCRC() +{ + uint8_t rv = _crc; + if (_reverseOut) rv = _reverse(rv); + rv ^= _endMask; + return rv; +} + + +void CRC8::_update(uint8_t value) +{ + if (!_started) restart(); + if (_reverseIn) value = _reverse(value); + _crc ^= value; + for (uint8_t i = 8; i; i--) + { + if (_crc & (1 << 7)) + { + _crc <<= 1; + _crc ^= _polynome; + } + else + { + _crc <<= 1; + } + } +} + + +uint8_t CRC8::_reverse(uint8_t in) +{ + uint8_t x = in; + x = (((x & 0xAA) >> 1) | ((x & 0x55) << 1)); + x = (((x & 0xCC) >> 2) | ((x & 0x33) << 2)); + x = ((x >> 4) | (x << 4)); + return x; +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/CRC8.h b/lib/CRC/CRC8.h new file mode 100644 index 0000000..22f0088 --- /dev/null +++ b/lib/CRC/CRC8.h @@ -0,0 +1,59 @@ +#pragma once +// +// FILE: CRC8.h +// AUTHOR: Rob Tillaart +// PURPOSE: Arduino class for CRC8 +// URL: https://github.com/RobTillaart/CRC + + +#include "Arduino.h" + +#define CRC8_DEFAULT_POLYNOME 0x07 + + +class CRC8 +{ +public: + CRC8(); + + // set parameters to default + void reset(); // set all to constructor defaults + void restart(); // reset crc with same parameters. + + // set parameters + void setPolynome(uint8_t polynome) { _polynome = polynome; }; + void setStartXOR(uint8_t start) { _startMask = start; }; + void setEndXOR(uint8_t end) { _endMask = end; }; + void setReverseIn(bool reverseIn) { _reverseIn = reverseIn; }; + void setReverseOut(bool reverseOut) { _reverseOut = reverseOut; }; + + // get parameters + uint8_t getPolynome() { return _polynome; }; + uint8_t getStartXOR() { return _startMask; }; + uint8_t getEndXOR() { return _endMask; }; + bool getReverseIn() { return _reverseIn; }; + bool getReverseOut() { return _reverseOut; }; + + void add(uint8_t value); + void add(const uint8_t * array, uint8_t length); + + uint8_t getCRC(); // returns CRC + uint32_t count() { return _count; }; + +private: + uint8_t _reverse(uint8_t value); + void _update(uint8_t value); + + uint8_t _polynome; + uint8_t _startMask; + uint8_t _endMask; + uint8_t _crc; + bool _reverseIn; + bool _reverseOut; + bool _started; + uint32_t _count; +}; + + +// -- END OF FILE -- + diff --git a/lib/CRC/LICENSE b/lib/CRC/LICENSE new file mode 100644 index 0000000..5777550 --- /dev/null +++ b/lib/CRC/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2021-2022 Rob Tillaart + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/lib/CRC/README.md b/lib/CRC/README.md new file mode 100644 index 0000000..d17ffeb --- /dev/null +++ b/lib/CRC/README.md @@ -0,0 +1,162 @@ + +[![Arduino CI](https://github.com/RobTillaart/CRC/workflows/Arduino%20CI/badge.svg)](https://github.com/marketplace/actions/arduino_ci) +[![Arduino-lint](https://github.com/RobTillaart/CRC/actions/workflows/arduino-lint.yml/badge.svg)](https://github.com/RobTillaart/CRC/actions/workflows/arduino-lint.yml) +[![JSON check](https://github.com/RobTillaart/CRC/actions/workflows/jsoncheck.yml/badge.svg)](https://github.com/RobTillaart/CRC/actions/workflows/jsoncheck.yml) +[![License: MIT](https://img.shields.io/badge/license-MIT-green.svg)](https://github.com/RobTillaart/CRC/blob/master/LICENSE) +[![GitHub release](https://img.shields.io/github/release/RobTillaart/CRC.svg?maxAge=3600)](https://github.com/RobTillaart/CRC/releases) + + +# CRC + +Arduino library with CRC8, CRC12, CRC16, CRC32 and CRC64 functions. + + +## Description + +Goal of this library is to have a flexible and portable set of generic +CRC functions and classes. + +The CRCx classes have a number of added values. Most important is that +they allow one to verify intermediate CRC values. This is useful if one +sends a "train of packets" which include a CRC so far. This detects both +errors in one packet but also missing packets, or injected packages. + +Another trick one can do is change the polynome or the reverse flag during +the process. This makes it harder to imitate. + +Furthermore the class allows to add values in single steps and continue too. + +Finally the class version gives more readable code (imho) as the parameters +are explicitly set. + + +**Note** the classes have same names as the static functions, except the class +is UPPER case. So CRC8 is a class and **crc8()** is the function. + +Deeper tech info -https://en.wikipedia.org/wiki/Cyclic_redundancy_check +and many other websites. + + +## Interface CRC classes + +These interfaces are very similar for CRC8, CRC12, CRC16, CRC32 and CRC64 class. +The only difference is the data type for polynome, start- and end-mask, +and the returned CRC. + +#### base + +Use **\#include "CRC8.h"** + +- **CRC8()** Constructor +- **void reset()** set all internals to constructor defaults. +- **void restart()** reset internal CRC and count only; reuse values for other +e.g polynome, XOR masks and reverse flags. +- **void add(value)** add a single value to CRC calculation. +- **void add(array, uint32_t length)** add an array of values to the CRC. +In case of a warning/error use casting to (uint8_t \*). +- **uint8_t getCRC()** returns CRC calculated so far. This allows to check the CRC of +a really large stream at intermediate moments, e.g. to link multiple packets. +- **uint32_t count()** returns number of values added so far. Default 0. + +#### parameters + +These parameters do not have defaults so the user must set them explicitly. + +- **void setPolynome(polynome)** set polynome, note reset sets a default polynome. +- **void setStartXOR(start)** set start-mask, default 0. +- **void setEndXOR(end)** set end-mask, default 0. +- **void setReverseIn(bool reverseIn)** reverse the bit pattern of input data (MSB vs LSB). +- **void setReverseOut(bool reverseOut)** reverse the bit pattern of CRC (MSB vs LSB). +- **uint8_t getPolyNome()** return parameter set above or default. +- **uint8_t getStartXOR()** return parameter set above or default. +- **uint8_t getEndXOR()** return parameter set above or default. +- **bool getReverseIn()** return parameter set above or default. +- **bool getReverseOut()** return parameter set above or default. + + +### Example snippet + +A minimal usage only needs: +- the constructor, the add() function and the getCRC() function. + +```cpp +#include "CRC32.h" +... + +CRC32 crc; + ... + while (Serial.available()) + { + int c = Serial.read(); + crc.add(c); + } + Serial.println(crc.getCRC()); +``` + + +## Interface static functions + +Use **\#include "CRC.h"** + +Most functions have a default polynome, same start and end masks, and default there is no reversing. +However these parameters allow one to tweak the CRC in all aspects known. +In all the examples encountered the reverse flags were set both to false or both to true. +For flexibility both parameters are kept available. + +- **uint8_t crc8(array, length, polynome = 0xD5, start = 0, end = 0, reverseIn = false, reverseOut = false)** idem with default polynome. +- **uint16_t crc12(array, length, polynome = 0x080D, start = 0, end = 0, reverseIn = false, reverseOut = false)** idem with default polynome. +- **uint16_t crc16(array, length, polynome = 0xA001, start = 0, end = 0, reverseIn = false, reverseOut = false)** idem with default polynome. +- **uint16_t crc16-CCITT(array, length)** fixed polynome **0x1021**, non zero start / end masks. +- **uint32_t crc32(array, length, polynome = 0x04C11DB7, start = 0, end = 0, reverseIn = false, reverseOut = false)** idem with default polynome. +- **uint64_t crc64(array, length, polynome, start, end, reverseIn, reverseOut)** - experimental version, no reference found except on Wikipedia. + +Note these functions are limited to one call per block of data. For more flexibility use the classes. + +The CRC functions also have fast reverse functions that can be used outside CRC context. +The usage is straightforward. + +- **uint8_t reverse8(uint8_t in)** idem. +- **uint16_t reverse16(uint16_t in)** idem. +- **uint16_t reverse12(uint16_t in)** idem. +- **uint32_t reverse32(uint32_t in)** idem. +- **uint64_t reverse64(uint64_t in)** idem. + +Reverse12 is based upon reverse16, with a final shift. +Other reverses can be created in similar way. + + +## Operational + +See examples. + + +## Links + +- https://en.wikipedia.org/wiki/Cyclic_redundancy_check - generic background. +- http://zorc.breitbandkatze.de/crc.html - online CRC calculator (any base up to 64 is supported.) +- https://crccalc.com/ - online CRC calculator to verify. + + +## Future + +- extend examples. + - example showing multiple packages of data linked by their CRC. +- setCRC(value) to be able to pick up where one left ? +- table versions for performance? (performance - memory discussion) +- add a dump(Stream = Serial) to see all the settings at once. +- stream version - 4 classes class? + + + +#### Exotic CRC's ? + +- **CRC1()** // parity :) +- **CRC4(array, length, polynome, start, end, reverseIn, reverseOut)** nibbles? + - default polynome 0x03 + + +#### Magic \#defines for "common" polynomes? verify ? + + - \#define CRC_ISO64 0x000000000000001B + - \#define CRC_ECMA64 0x42F0E1EBA9EA3693 + diff --git a/lib/CRC/examples/CRC12_test/CRC12_test.ino b/lib/CRC/examples/CRC12_test/CRC12_test.ino new file mode 100644 index 0000000..4641872 --- /dev/null +++ b/lib/CRC/examples/CRC12_test/CRC12_test.ino @@ -0,0 +1,102 @@ +// +// FILE: CRC16_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2022-01-24 +// (c) : MIT + + +#include "CRC12.h" +#include "CRC.h" + +char str1[24] = "123456789"; +char str2[24] = "123456789123456789"; + +CRC12 crc; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + // Serial.println("Verified with - http://zorc.breitbandkatze.de/crc.html \n"); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + Serial.println(crc_check((uint8_t *) str1, 9), HEX); + Serial.println(crc12((uint8_t *) str1, 9, 0x180D, 0, 0, false, false), HEX); + Serial.println(crc_check((uint8_t *) str2, 18), HEX); + Serial.println(crc12((uint8_t *) str2, 18, 0x180D, 0, 0, false, false), HEX); + + crc.setPolynome(0x080D); + crc.add((uint8_t*)str1, 9); + Serial.println(crc.getCRC(), HEX); + crc.reset(); + crc.setPolynome(0x080D); + crc.add((uint8_t*)str2, 18); + Serial.println(crc.getCRC(), HEX); + + + crc.reset(); + crc.setPolynome(0x180D); + for (int i = 0; i < 9; i++) + { + crc.add(str1[i]); + Serial.print(i); + Serial.print("\t"); + Serial.println(crc.getCRC(), HEX); + } + + crc.restart(); + for (int i = 0; i < 9; i++) + { + crc.add(str1[i]); + } + Serial.println(crc.getCRC(), HEX); + for (int i = 0; i < 9; i++) + { + crc.add(str1[i]); + } + Serial.println(crc.getCRC(), HEX); + Serial.println(crc.count()); +} + +//// +// reference function + +uint16_t crc_check(uint8_t * ptr, uint8_t length) // crc12 +{ + uint16_t crc12out = 0; + uint8_t i, j; + for (j = 0; j < length; j++) + { + for (i = 0; i < 8; i++) + { + if (*(ptr + j) & (0x80 >> i)) crc12out |= 0x01; + if (crc12out >= 0x1000) crc12out ^= 0x180D; + crc12out <<= 1; + } + } + for (i = 0; i < 12; i ++) + { + if (crc12out >= 0x1000) crc12out ^= 0x180D; + crc12out <<= 1; + } + crc12out >>= 1; + return crc12out; +} + + + + +// -- END OF FILE -- diff --git a/lib/CRC/examples/CRC16_test/CRC16_test.ino b/lib/CRC/examples/CRC16_test/CRC16_test.ino new file mode 100644 index 0000000..995fa9b --- /dev/null +++ b/lib/CRC/examples/CRC16_test/CRC16_test.ino @@ -0,0 +1,67 @@ +// +// FILE: CRC16_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2021-01-20 +// (c) : MIT + + +#include "CRC16.h" +#include "CRC.h" + +char str[24] = "123456789"; + +CRC16 crc; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + // Serial.println("Verified with - http://zorc.breitbandkatze.de/crc.html \n"); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + Serial.println(crc16((uint8_t *) str, 9, 0x1021, 0, 0, false, false), HEX); + + crc.setPolynome(0x1021); + crc.add((uint8_t*)str, 9); + Serial.println(crc.getCRC(), HEX); + + crc.reset(); + crc.setPolynome(0x1021); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + Serial.print(i); + Serial.print("\t"); + Serial.println(crc.getCRC(), HEX); + } + + crc.restart(); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + Serial.println(crc.count()); +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC32_performance/CRC32_performance.ino b/lib/CRC/examples/CRC32_performance/CRC32_performance.ino new file mode 100644 index 0000000..bf2b3cc --- /dev/null +++ b/lib/CRC/examples/CRC32_performance/CRC32_performance.ino @@ -0,0 +1,81 @@ +// +// FILE: CRC32_performance.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2022-01-28 +// (c) : MIT + + +#include "CRC32.h" + +char str[] = "Lorem ipsum dolor sit amet, \ +consectetuer adipiscing elit. Aenean commodo ligula eget dolor. \ +Aenean massa. Cum sociis natoque penatibus et magnis dis parturient \ +montes, nascetur ridiculus mus. Donec quam felis, ultricies nec, \ +pellentesque eu, pretium quis, sem. Nulla consequat massa quis enim. \ +Donec pede justo, fringilla vel, aliquet nec, vulputate eget, arcu. \ +In enim justo, rhoncus ut, imperdiet a, venenatis vitae, justo. \ +Nullam dictum felis eu pede mollis pretium. Integer tincidunt. \ +Cras dapibus. Vivamus elementum semper nisi. \ +Aenean vulputate eleifend tellus. Aenean leo ligula, porttitor eu, \ +consequat vitae, eleifend ac, enim. Aliquam lorem ante, dapibus in, \ +viverra quis, feugiat a, tellus. Phasellus viverra nulla ut metus \ +varius laoreet. Quisque rutrum. Aenean imperdiet. Etiam ultricies \ +nisi vel augue. Curabitur ullamcorper ultricies nisi. Nam eget dui."; + +CRC32 crc; + +uint32_t start, stop; + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + uint16_t length = strlen(str); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + start = micros(); + crc.add((uint8_t*)str, length); + stop = micros(); + Serial.print("DATA: \t"); + Serial.println(length); + Serial.print(" CRC:\t"); + Serial.println(crc.getCRC(), HEX); + Serial.print("TIME: \t"); + Serial.println(stop - start); + Serial.println(); + delay(100); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + crc.setReverseIn(true); + start = micros(); + crc.add((uint8_t*)str, length); + stop = micros(); + Serial.print("DATA: \t"); + Serial.println(length); + Serial.print(" CRC:\t"); + Serial.println(crc.getCRC(), HEX); + Serial.print("TIME: \t"); + Serial.println(stop - start); + delay(100); + + + +} + + +// -- END OF FILE -- diff --git a/lib/CRC/examples/CRC32_performance/performance_0.2.0.txt b/lib/CRC/examples/CRC32_performance/performance_0.2.0.txt new file mode 100644 index 0000000..feb12a4 --- /dev/null +++ b/lib/CRC/examples/CRC32_performance/performance_0.2.0.txt @@ -0,0 +1,13 @@ + +Tested on UNO +IDE 1.18.19 + +CRC32_performance.ino +DATA: 868 + CRC: 2DFE771A +TIME: 852 + +DATA: 868 + CRC: 9604D4F8 +TIME: 920 + diff --git a/lib/CRC/examples/CRC32_test/CRC32_test.ino b/lib/CRC/examples/CRC32_test/CRC32_test.ino new file mode 100644 index 0000000..7112e6a --- /dev/null +++ b/lib/CRC/examples/CRC32_test/CRC32_test.ino @@ -0,0 +1,62 @@ +// +// FILE: CRC32_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2021-01-20 +// (c) : MIT + + +#include "CRC32.h" + +char str[24] = "123456789"; + +CRC32 crc; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + // Serial.println("Verified with - http://zorc.breitbandkatze.de/crc.html \n"); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + crc.setPolynome(0x04C11DB7); + crc.add((uint8_t*)str, 9); + Serial.println(crc.getCRC(), HEX); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + + crc.restart(); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + Serial.println(crc.count()); +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC64_test/CRC64_test.ino b/lib/CRC/examples/CRC64_test/CRC64_test.ino new file mode 100644 index 0000000..18cd724 --- /dev/null +++ b/lib/CRC/examples/CRC64_test/CRC64_test.ino @@ -0,0 +1,63 @@ +// +// FILE: CRC64_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2021-01-20 +// (c) : MIT + + +#include "CRC64.h" +#include "printHelpers.h" // https://github.com/RobTillaart/printHelpers + +char str[24] = "123456789"; + +CRC64 crc; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + // Serial.println("Verified with - http://zorc.breitbandkatze.de/crc.html \n"); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + crc.setPolynome(0x07); + crc.add((uint8_t*)str, 9); + Serial.println(print64(crc.getCRC(), HEX)); + + crc.reset(); + crc.setPolynome(0x07); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(print64(crc.getCRC(), HEX)); + + crc.restart(); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(print64(crc.getCRC(), HEX)); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(print64(crc.getCRC(), HEX)); + Serial.println(print64(crc.count())); +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC8_test/CRC8_test.ino b/lib/CRC/examples/CRC8_test/CRC8_test.ino new file mode 100644 index 0000000..5c356b3 --- /dev/null +++ b/lib/CRC/examples/CRC8_test/CRC8_test.ino @@ -0,0 +1,66 @@ +// +// FILE: CRC8_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2021-01-20 +// (c) : MIT + + +#include "CRC8.h" +#include "CRC.h" + + +char str[24] = "123456789"; + +CRC8 crc; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + // Serial.println("Verified with - http://zorc.breitbandkatze.de/crc.html \n"); + + test(); +} + + +void loop() +{ +} + + +void test() +{ + Serial.println(crc8((uint8_t *)str, 9, 0x07), HEX); + + crc.setPolynome(0x07); + crc.add((uint8_t*)str, 9); + Serial.println(crc.getCRC(), HEX); + + crc.reset(); + crc.setPolynome(0x07); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + + crc.restart(); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + for (int i = 0; i < 9; i++) + { + crc.add(str[i]); + } + Serial.println(crc.getCRC(), HEX); + Serial.println(crc.count()); +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC_performance/CRC_performance.ino b/lib/CRC/examples/CRC_performance/CRC_performance.ino new file mode 100644 index 0000000..833e71d --- /dev/null +++ b/lib/CRC/examples/CRC_performance/CRC_performance.ino @@ -0,0 +1,118 @@ +// +// FILE: CRC_performance.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2020 +// (c) : MIT +// + + +#include "CRC.h" + +char str[122] = "123456789012345678901234567890123456789012345678901234567890123456789012345678901234567890"; + +uint32_t start, stop; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + uint8_t * data = (uint8_t *) &str[0]; + uint8_t len = strlen(str); + + Serial.println("Calculating CRC of 100 bytes message\n"); + delay(100); + + start = micros(); + uint8_t x8 = crc8(data, len, 0x07, 0x00, 0x00, false, false); + stop = micros(); + Serial.print("CRC8:\t"); + Serial.println(x8, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + delay(100); + + start = micros(); + x8 = crc8(data, len, 0x07, 0x00, 0x00, true, true); + stop = micros(); + Serial.print("CRC8:\t"); + Serial.println(x8, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + Serial.println("============================="); + delay(100); + + + start = micros(); + uint16_t x16 = crc16(data, len, 0x1021, 0xFFFF, 0x0000, false, false ); + stop = micros(); + Serial.print("CRC16:\t"); + Serial.println(x16, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + delay(100); + + start = micros(); + x16 = crc16(data, len, 0x1021, 0xFFFF, 0x0000, true, true ); + stop = micros(); + Serial.print("CRC16:\t"); + Serial.println(x16, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + Serial.println("============================="); + delay(100); + + + start = micros(); + uint32_t x32 = crc32(data, len, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false); + stop = micros(); + Serial.print("CRC32:\t"); + Serial.println(x32, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + delay(100); + + start = micros(); + x32 = crc32(data, len, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true); + stop = micros(); + Serial.print("CRC32:\t"); + Serial.println(x32, HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + Serial.println("============================="); + delay(100); + + start = micros(); + uint64_t x64 = crc64(data, len, 0x814141AB, 0x00000000, 0x00000000, false, false); + stop = micros(); + Serial.print("CRC64:\t"); + Serial.print((uint32_t)(x64 >> 32), HEX); + Serial.println((uint32_t)(x64 & 0xFFFFFFFF), HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + delay(100); + + start = micros(); + x64 = crc64(data, len, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true); + stop = micros(); + Serial.print("CRC64:\t"); + Serial.print((uint32_t)(x64 >> 32), HEX); + Serial.println((uint32_t)(x64 & 0xFFFFFFFF), HEX); + Serial.print("TIME:\t"); + Serial.println(stop - start); + Serial.println("============================="); + delay(100); + + Serial.println("\n\nDone..."); +} + + +void loop() +{ +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC_reference_test/CRC_reference_test.ino b/lib/CRC/examples/CRC_reference_test/CRC_reference_test.ino new file mode 100644 index 0000000..72a8636 --- /dev/null +++ b/lib/CRC/examples/CRC_reference_test/CRC_reference_test.ino @@ -0,0 +1,97 @@ +// +// FILE: CRC_reference_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2020 +// (c) : MIT +// + + +#include "CRC.h" +#include "printHelpers.h" // for the 64 bit... + +char str[24] = "123456789"; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + uint8_t * data = (uint8_t *) &str[0]; + + Serial.println("Verified with - https://crccalc.com/ \n"); + + + Serial.print("TEST:\t"); + Serial.println(str); + Serial.println("\nCRC8\n--------------------"); + Serial.println(crc8(data, 9, 0x07), HEX); + Serial.println(crc8(data, 9, 0x9B, 0xFF), HEX); + Serial.println(crc8(data, 9, 0x39, 0x00, 0x00, true, true), HEX); + Serial.println(crc8(data, 9, 0xD5), HEX); + Serial.println(crc8(data, 9, 0x1D, 0xFF, 0x00, true, true), HEX); + Serial.println(crc8(data, 9, 0x1D, 0xFD), HEX); + Serial.println(crc8(data, 9, 0x07, 0x00, 0x55), HEX); + Serial.println(crc8(data, 9, 0x31, 0x00, 0x00, true, true), HEX); + Serial.println(crc8(data, 9, 0x07, 0xFF, 0x00, true, true), HEX); + Serial.println(crc8(data, 9, 0x9B, 0x00, 0x00, true, true), HEX); + Serial.println(); + + + Serial.println("CRC16\n--------------------"); + Serial.println(crc16(data, 9, 0x1021, 0xFFFF, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0x0000, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0x1D0F, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0x0000, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0xC867, 0xFFFF, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0x800D, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x0589, 0x0000, 0x0001, false, false ), HEX); + Serial.println(crc16(data, 9, 0x0589, 0x0000, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, true, true ), HEX); + Serial.println(crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, false, false ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, false, false ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0x0000, 0xFFFF, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0xFFFF, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0xB2AA, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x8BB7, 0x0000, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0xA097, 0x0000, 0x0000, false, false ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0x89EC, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0xFFFF, 0xFFFF, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0xC6C6, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0x0000, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x8005, 0xFFFF, 0x0000, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, true, true ), HEX); + Serial.println(crc16(data, 9, 0x1021, 0x0000, 0x0000, false, false ), HEX); + Serial.println(); + + + Serial.println("CRC32\n--------------------"); + Serial.println(crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true), HEX); + Serial.println(crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false), HEX); + Serial.println(crc32(data, 9, 0x1EDC6F41, 0xFFFFFFFF, 0xFFFFFFFF, true, true), HEX); + Serial.println(crc32(data, 9, 0xA833982B, 0xFFFFFFFF, 0xFFFFFFFF, true, true), HEX); + Serial.println(crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, false, false), HEX); + Serial.println(crc32(data, 9, 0x04C11DB7, 0x00000000, 0xFFFFFFFF, false, false), HEX); + Serial.println(crc32(data, 9, 0x814141AB, 0x00000000, 0x00000000, false, false), HEX); + Serial.println(crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, true, true), HEX); + Serial.println(crc32(data, 9, 0x000000AF, 0x00000000, 0x00000000, false, false), HEX); + Serial.println(); + + + Serial.println("\nCRC64 - no reference\n--------------------"); + uint64_t t = crc64(data, 9, 0x814141AB, 0x00000000, 0x00000000, false, false); + Serial.println(print64(t, HEX)); + + + Serial.println("\n\nDone..."); +} + + +void loop() +{ +} + + +// -- END OF FILE -- + diff --git a/lib/CRC/examples/CRC_test/CRC_test.ino b/lib/CRC/examples/CRC_test/CRC_test.ino new file mode 100644 index 0000000..1a9871f --- /dev/null +++ b/lib/CRC/examples/CRC_test/CRC_test.ino @@ -0,0 +1,46 @@ +// +// FILE: CRC_test.ino +// AUTHOR: Rob Tillaart +// PURPOSE: demo +// DATE: 2020 +// (c) : MIT +// + + +#include "CRC.h" +#include "printHelpers.h" // for the 64 bit... + +char str[24] = "123456789"; + + +void setup() +{ + Serial.begin(115200); + Serial.println(__FILE__); + + uint8_t * data = (uint8_t *) &str[0]; + + Serial.println("Verified with - https://crccalc.com/ \n"); + + Serial.print("TEST:\t"); + Serial.println(str); + Serial.print("CRC8:\t"); + Serial.println(crc8(data, 9, 0x07, 0x00, 0x00, false, false), HEX); + Serial.print("CRC16:\t"); + Serial.println(crc16(data, 9, 0x1021, 0x0000, 0x0000, false, false ), HEX); + Serial.print("CRC32:\t"); + Serial.println(crc32(data, 9, 0x04C11DB7, 0x00000000, 0x00000000, false, false), HEX); +// Serial.print("*CRC64:\t"); +// uint64_t t = crc64(data, 9, 0x814141AB, 0x00000000, 0x00000000, false, false); +// Serial.println(print64(t, HEX)); + + Serial.println("\n\nDone..."); +} + + +void loop() +{ +} + + +// -- END OF FILE -- diff --git a/lib/CRC/keywords.txt b/lib/CRC/keywords.txt new file mode 100644 index 0000000..d896bbe --- /dev/null +++ b/lib/CRC/keywords.txt @@ -0,0 +1,42 @@ +# Syntax Colouring Map For CRC + +# Data types (KEYWORD1) +CRC8 KEYWORD1 +CRC12 KEYWORD1 +CRC16 KEYWORD1 +CRC32 KEYWORD1 +CRC64 KEYWORD1 + +# Methods and Functions (KEYWORD2) +crc8 KEYWORD2 +crc12 KEYWORD2 +crc16 KEYWORD2 +crc16_CCITT KEYWORD2 +crc32 KEYWORD2 +crc64 KEYWORD2 + +reset KEYWORD2 +restart KEYWORD2 + +setPolynome KEYWORD2 +setStartXOR KEYWORD2 +setEndXOR KEYWORD2 +setReverseIn KEYWORD2 +setReverseOut KEYWORD2 + +getPolynome KEYWORD2 +getStartXOR KEYWORD2 +getEndXOR KEYWORD2 +getReverseIn KEYWORD2 +getReverseOut KEYWORD2 + +add KEYWORD2 +getCRC KEYWORD2 +count KEYWORD2 + +# Instances (KEYWORD2) + + +# Constants (LITERAL1) +CRC_LIB_VERSION LITERAL1 + diff --git a/lib/CRC/library.json b/lib/CRC/library.json new file mode 100644 index 0000000..d0430d3 --- /dev/null +++ b/lib/CRC/library.json @@ -0,0 +1,23 @@ +{ + "name": "CRC", + "keywords": "CRC8,CRC12,CRC16,CRC16-CCITT,CRC32,CRC64", + "description": "Library for CRC for Arduino.", + "authors": + [ + { + "name": "Rob Tillaart", + "email": "Rob.Tillaart@gmail.com", + "maintainer": true + } + ], + "repository": + { + "type": "git", + "url": "https://github.com/RobTillaart/CRC" + }, + "version": "0.2.0", + "license": "MIT", + "frameworks": "arduino", + "platforms": "*", + "headers": "CRC.h" +} diff --git a/lib/CRC/library.properties b/lib/CRC/library.properties new file mode 100644 index 0000000..933a8a4 --- /dev/null +++ b/lib/CRC/library.properties @@ -0,0 +1,11 @@ +name=CRC +version=0.2.0 +author=Rob Tillaart +maintainer=Rob Tillaart +sentence=Library for CRC for Arduino +paragraph=CRC8, CRC12, CRC16, CRC16-CCITT, CRC32, CRC64 +category=Data Processing +url=https://github.com/RobTillaart/CRC +architectures=* +includes=CRC.h,CRC8.h,CRC12.h, CRC16.h,CRC32.h,CRC64.h +depends= diff --git a/lib/CRC/releaseNotes.md b/lib/CRC/releaseNotes.md new file mode 100644 index 0000000..7015016 --- /dev/null +++ b/lib/CRC/releaseNotes.md @@ -0,0 +1,22 @@ + +# Release Notes + + +## 0.2.0 + +- added getters for parameters +- made yield conditional in the add(array, length) +- improved examples +- added releaseNotes.md + + +## 0.1.6 + +- add CRC12 function +- add CRC12 class + + +## 0.1.5 + +- TODO (just as older versions) + diff --git a/lib/CRC/test/unit_test_001.cpp b/lib/CRC/test/unit_test_001.cpp new file mode 100644 index 0000000..7a86220 --- /dev/null +++ b/lib/CRC/test/unit_test_001.cpp @@ -0,0 +1,120 @@ +// +// FILE: unit_test_001.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-01-01 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ + fprintf(stderr, "CRC_LIB_VERSION: %s\n", (char *) CRC_LIB_VERSION); +} + +unittest_teardown() +{ +} + + +unittest(test_crc8) +{ + assertEqual(0xF4, crc8(data, 9, 0x07)); + assertEqual(0xDA, crc8(data, 9, 0x9B, 0xFF)); + assertEqual(0x15, crc8(data, 9, 0x39, 0x00, 0x00, true, true)); + assertEqual(0xBC, crc8(data, 9, 0xD5)); + assertEqual(0x97, crc8(data, 9, 0x1D, 0xFF, 0x00, true, true)); + assertEqual(0x7E, crc8(data, 9, 0x1D, 0xFD)); + assertEqual(0xA1, crc8(data, 9, 0x07, 0x00, 0x55)); + assertEqual(0xA1, crc8(data, 9, 0x31, 0x00, 0x00, true, true)); + assertEqual(0xD0, crc8(data, 9, 0x07, 0xFF, 0x00, true, true)); + assertEqual(0x25, crc8(data, 9, 0x9B, 0x00, 0x00, true, true)); +} + + +unittest(test_crc16) +{ + assertEqual(0x29B1, crc16(data, 9, 0x1021, 0xFFFF, 0x0000, false, false )); + assertEqual(0xBB3D, crc16(data, 9, 0x8005, 0x0000, 0x0000, true, true )); + assertEqual(0xE5CC, crc16(data, 9, 0x1021, 0x1D0F, 0x0000, false, false )); + assertEqual(0xFEE8, crc16(data, 9, 0x8005, 0x0000, 0x0000, false, false )); + assertEqual(0x4C06, crc16(data, 9, 0xC867, 0xFFFF, 0x0000, false, false )); + assertEqual(0x9ECF, crc16(data, 9, 0x8005, 0x800D, 0x0000, false, false )); + assertEqual(0x007E, crc16(data, 9, 0x0589, 0x0000, 0x0001, false, false )); + assertEqual(0x007F, crc16(data, 9, 0x0589, 0x0000, 0x0000, false, false )); + assertEqual(0xEA82, crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, true, true )); + assertEqual(0xC2B7, crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, false, false )); + assertEqual(0xD64E, crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, false, false )); + assertEqual(0x44C2, crc16(data, 9, 0x8005, 0x0000, 0xFFFF, true, true )); + assertEqual(0x6F91, crc16(data, 9, 0x1021, 0xFFFF, 0x0000, true, true )); + assertEqual(0x63D0, crc16(data, 9, 0x1021, 0xB2AA, 0x0000, true, true )); + assertEqual(0xD0DB, crc16(data, 9, 0x8BB7, 0x0000, 0x0000, false, false )); + assertEqual(0x0FB3, crc16(data, 9, 0xA097, 0x0000, 0x0000, false, false )); + assertEqual(0x26B1, crc16(data, 9, 0x1021, 0x89EC, 0x0000, true, true )); + assertEqual(0xB4C8, crc16(data, 9, 0x8005, 0xFFFF, 0xFFFF, true, true )); + assertEqual(0xBF05, crc16(data, 9, 0x1021, 0xC6C6, 0x0000, true, true )); + assertEqual(0x2189, crc16(data, 9, 0x1021, 0x0000, 0x0000, true, true )); + assertEqual(0x4B37, crc16(data, 9, 0x8005, 0xFFFF, 0x0000, true, true )); + assertEqual(0x906E, crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, true, true )); + assertEqual(0x31C3, crc16(data, 9, 0x1021, 0x0000, 0x0000, false, false )); +} + + +unittest(test_crc32) +{ + assertEqual(0xCBF43926, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0xFC891918, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false)); + assertEqual(0xE3069283, crc32(data, 9, 0x1EDC6F41, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0x87315576, crc32(data, 9, 0xA833982B, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0x0376E6E7, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, false, false)); + assertEqual(0x765E7680, crc32(data, 9, 0x04C11DB7, 0x00000000, 0xFFFFFFFF, false, false)); + assertEqual(0x3010BF7F, crc32(data, 9, 0x814141AB, 0x00000000, 0x00000000, false, false)); + assertEqual(0x340BC6D9, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, true, true)); + assertEqual(0xBD0BE338, crc32(data, 9, 0x000000AF, 0x00000000, 0x00000000, false, false)); +} + + +unittest(test_crc64) +{ + fprintf(stderr, "no reference yet\n"); + assertEqual(1, 1); +} + + +unittest_main() + +// -------- diff --git a/lib/CRC/test/unit_test_crc12.cpp b/lib/CRC/test/unit_test_crc12.cpp new file mode 100644 index 0000000..7b88d53 --- /dev/null +++ b/lib/CRC/test/unit_test_crc12.cpp @@ -0,0 +1,94 @@ +// +// FILE: unit_test_crc16.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-03-31 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC12.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ +} + +unittest_teardown() +{ +} + + +unittest(test_crc12_getters) +{ + fprintf(stderr, "TEST CRC12 GETTERS\n"); + + CRC12 crc; + crc.setPolynome(0x080D); + crc.setStartXOR(0x0555); + crc.setEndXOR(0x0AAA); + crc.setReverseIn(true); + crc.setReverseOut(false); + + assertEqual(0x080D, crc.getPolynome()); + assertEqual(0x0555, crc.getStartXOR()); + assertEqual(0x0AAA, crc.getEndXOR()); + assertTrue(crc.getReverseIn()); + assertFalse(crc.getReverseOut()); +} + + +unittest(test_crc12) +{ + fprintf(stderr, "TEST CRC12\n"); + + CRC12 crc; + crc.setPolynome(0x080D); + crc.add(data, 9); + assertEqual(0xEFB, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x080D); + crc.add(data, 9); + crc.add(data, 9); + assertEqual(0x1B3, crc.getCRC()); + + // TODO extend + +} + + +unittest_main() + +// -------- diff --git a/lib/CRC/test/unit_test_crc16.cpp b/lib/CRC/test/unit_test_crc16.cpp new file mode 100644 index 0000000..852d1c9 --- /dev/null +++ b/lib/CRC/test/unit_test_crc16.cpp @@ -0,0 +1,309 @@ +// +// FILE: unit_test_crc16.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-03-31 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC16.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ +} + +unittest_teardown() +{ +} + + +unittest(test_crc16_getters) +{ + fprintf(stderr, "TEST CRC16 GETTERS\n"); + + CRC16 crc; + crc.setPolynome(0x1021); + crc.setStartXOR(0x1D0F); + crc.setEndXOR(0x8007); + crc.setReverseIn(true); + crc.setReverseOut(false); + + assertEqual(0x1021, crc.getPolynome()); + assertEqual(0x1D0F, crc.getStartXOR()); + assertEqual(0x8007, crc.getEndXOR()); + assertTrue(crc.getReverseIn()); + assertFalse(crc.getReverseOut()); +} + + +unittest(test_crc16) +{ + fprintf(stderr, "TEST CRC16\n"); + + CRC16 crc; + crc.setPolynome(0x1021); + crc.setStartXOR(0xFFFF); + crc.add(data, 9); + assertEqual(0x29B1, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xBB3D, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0x1D0F); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xE5CC, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xFEE8, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0xC867); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x4C06, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setStartXOR(0x800D); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x9ECF, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x0589); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0001); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x007E, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x0589); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x007F, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x3D65); + crc.setStartXOR(0x0000); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xEA82, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x3D65); + crc.setStartXOR(0x0000); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xC2B7, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xD64E, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setStartXOR(0x0000); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x44C2, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x6F91, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0xB2AA); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x63D0, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8BB7); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xD0DB, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0xA097); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x0FB3, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0x89EC); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x26B1, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xB4C8, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0xC6C6); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xBF05, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x2189, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x8005); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0x0000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x4B37, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0xFFFF); + crc.setEndXOR(0xFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x906E, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1021); + crc.setStartXOR(0x0000); + crc.setEndXOR(0x0000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x31C3, crc.getCRC()); + + + /* + assertEqual(0x29B1, crc16(data, 9, 0x1021, 0xFFFF, 0x0000, false, false )); + assertEqual(0xBB3D, crc16(data, 9, 0x8005, 0x0000, 0x0000, true, true )); + assertEqual(0xE5CC, crc16(data, 9, 0x1021, 0x1D0F, 0x0000, false, false )); + assertEqual(0xFEE8, crc16(data, 9, 0x8005, 0x0000, 0x0000, false, false )); + assertEqual(0x4C06, crc16(data, 9, 0xC867, 0xFFFF, 0x0000, false, false )); + assertEqual(0x9ECF, crc16(data, 9, 0x8005, 0x800D, 0x0000, false, false )); + assertEqual(0x007E, crc16(data, 9, 0x0589, 0x0000, 0x0001, false, false )); + assertEqual(0x007F, crc16(data, 9, 0x0589, 0x0000, 0x0000, false, false )); + assertEqual(0xEA82, crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, true, true )); + assertEqual(0xC2B7, crc16(data, 9, 0x3D65, 0x0000, 0xFFFF, false, false )); + assertEqual(0xD64E, crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, false, false )); + assertEqual(0x44C2, crc16(data, 9, 0x8005, 0x0000, 0xFFFF, true, true )); + assertEqual(0x6F91, crc16(data, 9, 0x1021, 0xFFFF, 0x0000, true, true )); + assertEqual(0x63D0, crc16(data, 9, 0x1021, 0xB2AA, 0x0000, true, true )); + assertEqual(0xD0DB, crc16(data, 9, 0x8BB7, 0x0000, 0x0000, false, false )); + assertEqual(0x0FB3, crc16(data, 9, 0xA097, 0x0000, 0x0000, false, false )); + assertEqual(0x26B1, crc16(data, 9, 0x1021, 0x89EC, 0x0000, true, true )); + assertEqual(0xB4C8, crc16(data, 9, 0x8005, 0xFFFF, 0xFFFF, true, true )); + assertEqual(0xBF05, crc16(data, 9, 0x1021, 0xC6C6, 0x0000, true, true )); + assertEqual(0x2189, crc16(data, 9, 0x1021, 0x0000, 0x0000, true, true )); + assertEqual(0x4B37, crc16(data, 9, 0x8005, 0xFFFF, 0x0000, true, true )); + assertEqual(0x906E, crc16(data, 9, 0x1021, 0xFFFF, 0xFFFF, true, true )); + assertEqual(0x31C3, crc16(data, 9, 0x1021, 0x0000, 0x0000, false, false )); + */ +} + + +unittest_main() + +// -------- diff --git a/lib/CRC/test/unit_test_crc32.cpp b/lib/CRC/test/unit_test_crc32.cpp new file mode 100644 index 0000000..e2b4bcb --- /dev/null +++ b/lib/CRC/test/unit_test_crc32.cpp @@ -0,0 +1,185 @@ +// +// FILE: unit_test_crc32.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-03-31 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC32.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ +} + +unittest_teardown() +{ +} + + +unittest(test_crc32_getters) +{ + fprintf(stderr, "TEST CRC32 GETTERS\n"); + + CRC32 crc; + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0xFFFFFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + + assertEqual(0x04C11DB7, crc.getPolynome()); + assertEqual(0xFFFFFFFF, crc.getStartXOR()); + assertEqual(0xFFFFFFFF, crc.getEndXOR()); + assertTrue(crc.getReverseIn()); + assertTrue(crc.getReverseOut()); + + crc.reset(); + crc.setPolynome(0x1EDC6F41); + crc.setStartXOR(0x00000000); + crc.setEndXOR(0x00000000); + crc.setReverseIn(false); + crc.setReverseOut(false); + + assertEqual(0x1EDC6F41, crc.getPolynome()); + assertEqual(0x00000000, crc.getStartXOR()); + assertEqual(0x00000000, crc.getEndXOR()); + assertFalse(crc.getReverseIn()); + assertFalse(crc.getReverseOut()); +} + + +unittest(test_crc32) +{ + fprintf(stderr, "TEST CRC32\n"); + + CRC32 crc; + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0xFFFFFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xCBF43926, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0xFFFFFFFF); + crc.add(data, 9); + assertEqual(0xFC891918, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1EDC6F41); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0xFFFFFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xE3069283, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0xA833982B); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0xFFFFFFFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x87315576, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0x00000000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x0376E6E7, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0x00000000); + crc.setEndXOR(0xFFFFFFFF); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x765E7680, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x814141AB); + crc.setStartXOR(0x00000000); + crc.setEndXOR(0x00000000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0x3010BF7F, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x04C11DB7); + crc.setStartXOR(0xFFFFFFFF); + crc.setEndXOR(0x00000000); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x340BC6D9, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x000000AF); + crc.setStartXOR(0x00000000); + crc.setEndXOR(0x00000000); + crc.setReverseIn(false); + crc.setReverseOut(false); + crc.add(data, 9); + assertEqual(0xBD0BE338, crc.getCRC()); + + /* + // DONE + assertEqual(0xCBF43926, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0xFC891918, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0xFFFFFFFF, false, false)); + assertEqual(0xE3069283, crc32(data, 9, 0x1EDC6F41, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0x87315576, crc32(data, 9, 0xA833982B, 0xFFFFFFFF, 0xFFFFFFFF, true, true)); + assertEqual(0x0376E6E7, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, false, false)); + assertEqual(0x765E7680, crc32(data, 9, 0x04C11DB7, 0x00000000, 0xFFFFFFFF, false, false)); + assertEqual(0x3010BF7F, crc32(data, 9, 0x814141AB, 0x00000000, 0x00000000, false, false)); + assertEqual(0x340BC6D9, crc32(data, 9, 0x04C11DB7, 0xFFFFFFFF, 0x00000000, true, true)); + assertEqual(0xBD0BE338, crc32(data, 9, 0x000000AF, 0x00000000, 0x00000000, false, false)); + */ +} + + +unittest_main() + +// -------- diff --git a/lib/CRC/test/unit_test_crc64.cpp b/lib/CRC/test/unit_test_crc64.cpp new file mode 100644 index 0000000..1470270 --- /dev/null +++ b/lib/CRC/test/unit_test_crc64.cpp @@ -0,0 +1,89 @@ +// +// FILE: unit_test_crc64.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-03-31 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC64.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ +} + +unittest_teardown() +{ +} + + +unittest(test_crc64_getters) +{ + fprintf(stderr, "TEST CRC64 GETTERS\n"); + + CRC64 crc; + crc.setPolynome(0x04C11DB704C11DB7); + crc.setStartXOR(0xCE5CA2AD34A16112); + crc.setEndXOR(0x2AD34A16112CE5CA); + crc.setReverseIn(false); + crc.setReverseOut(false); + + assertEqual(0x04C11DB704C11DB7, crc.getPolynome()); + assertEqual(0xCE5CA2AD34A16112, crc.getStartXOR()); + assertEqual(0x2AD34A16112CE5CA, crc.getEndXOR()); + assertFalse(crc.getReverseIn()); + assertFalse(crc.getReverseOut()); +} + + +unittest(test_crc64) +{ + fprintf(stderr, "TEST CRC64\n"); + + fprintf(stderr, "no reference yet\n"); + assertEqual(1, 1); + + // just a dummy test + CRC64 crc; + crc.setPolynome(0x04C11DB704C11DB7); + crc.add(data, 9); + assertEqual(0xCE5CA2AD34A16112, crc.getCRC()); // 14869938934466568466 +} + + +unittest_main() + +// -------- diff --git a/lib/CRC/test/unit_test_crc8.cpp b/lib/CRC/test/unit_test_crc8.cpp new file mode 100644 index 0000000..3959d48 --- /dev/null +++ b/lib/CRC/test/unit_test_crc8.cpp @@ -0,0 +1,155 @@ +// +// FILE: unit_test_crc8.cpp +// AUTHOR: Rob Tillaart +// DATE: 2021-03-31 +// PURPOSE: unit tests for the CRC library +// https://github.com/RobTillaart/CRC +// https://github.com/Arduino-CI/arduino_ci/blob/master/REFERENCE.md +// + +// supported assertions +// ---------------------------- +// assertEqual(expected, actual); // a == b +// assertNotEqual(unwanted, actual); // a != b +// assertComparativeEquivalent(expected, actual); // abs(a - b) == 0 or (!(a > b) && !(a < b)) +// assertComparativeNotEquivalent(unwanted, actual); // abs(a - b) > 0 or ((a > b) || (a < b)) +// assertLess(upperBound, actual); // a < b +// assertMore(lowerBound, actual); // a > b +// assertLessOrEqual(upperBound, actual); // a <= b +// assertMoreOrEqual(lowerBound, actual); // a >= b +// assertTrue(actual); +// assertFalse(actual); +// assertNull(actual); + +// // special cases for floats +// assertEqualFloat(expected, actual, epsilon); // fabs(a - b) <= epsilon +// assertNotEqualFloat(unwanted, actual, epsilon); // fabs(a - b) >= epsilon +// assertInfinity(actual); // isinf(a) +// assertNotInfinity(actual); // !isinf(a) +// assertNAN(arg); // isnan(a) +// assertNotNAN(arg); // !isnan(a) + + +#include + + +#include "Arduino.h" +#include "CRC8.h" + + +char str[24] = "123456789"; +uint8_t * data = (uint8_t *) str; + + +unittest_setup() +{ +} + + +unittest_teardown() +{ +} + + +unittest(test_crc8_getters) +{ + fprintf(stderr, "TEST CRC8 GETTERS\n"); + + CRC8 crc; + crc.setPolynome(0x07); + crc.setStartXOR(0x55); + crc.setEndXOR(0xAA); + crc.setReverseIn(false); + crc.setReverseOut(true); + + assertEqual(0x07, crc.getPolynome()); + assertEqual(0x55, crc.getStartXOR()); + assertEqual(0xAA, crc.getEndXOR()); + assertFalse(crc.getReverseIn()); + assertTrue(crc.getReverseOut()); +} + + +unittest(test_crc8) +{ + fprintf(stderr, "TEST CRC8\n"); + + CRC8 crc; + crc.setPolynome(0x07); + crc.add(data, 9); + assertEqual(0xF4, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x39); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x15, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0xD5); + crc.add(data, 9); + assertEqual(0xBC, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1D); + crc.setStartXOR(0xFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x97, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x1D); + crc.setStartXOR(0xFD); + crc.add(data, 9); + assertEqual(0x7E, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x07); + crc.setStartXOR(0x00); + crc.setEndXOR(0x55); + crc.add(data, 9); + assertEqual(0xA1, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x31); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xA1, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x07); + crc.setStartXOR(0xFF); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0xD0, crc.getCRC()); + + crc.reset(); + crc.setPolynome(0x9B); + crc.setReverseIn(true); + crc.setReverseOut(true); + crc.add(data, 9); + assertEqual(0x25, crc.getCRC()); + + + /* + // DONE + assertEqual(0xDA, crc8(data, 9, 0x9B, 0xFF)); + assertEqual(0x15, crc8(data, 9, 0x39, 0x00, 0x00, true, true)); + assertEqual(0xBC, crc8(data, 9, 0xD5)); + assertEqual(0x97, crc8(data, 9, 0x1D, 0xFF, 0x00, true, true)); + assertEqual(0x7E, crc8(data, 9, 0x1D, 0xFD)); + assertEqual(0xA1, crc8(data, 9, 0x07, 0x00, 0x55)); + assertEqual(0xA1, crc8(data, 9, 0x31, 0x00, 0x00, true, true)); + assertEqual(0xD0, crc8(data, 9, 0x07, 0xFF, 0x00, true, true)); + assertEqual(0x25, crc8(data, 9, 0x9B, 0x00, 0x00, true, true)); + */ +} + + +unittest_main() + +// -------- diff --git a/lib/DRV10970/src/DRV_10970.cpp b/lib/DRV10970/src/DRV_10970.cpp new file mode 100644 index 0000000..50f6d69 --- /dev/null +++ b/lib/DRV10970/src/DRV_10970.cpp @@ -0,0 +1,90 @@ +/**************************************************************** + * Library for interfacing with the DRV 10970 motor driver. + * + * @author: Garrett Wells + * @date: 01/18/22 + * + * Provides a configurable interface for working with the DRV 10970 motor driver. Initially written for University of Idaho senior capstone 2022 for use by the + * Attitude adjustment team working for NASA. + ****************************************************************/ +#include "DRV_10970.h" + +DRV10970::DRV10970(int fg, int fr, int brkmod, int pwm, int rd){ + FG = fg; // frequency indication pin + FR = fr; // motor direction control + BRKMOD = brkmod; // brake mode setting pin + PWM = pwm; // variable duty cycle pwm input pin for speed control + RD = rd; // lock indication pin + // set pin modes + pinMode(FG, INPUT); + pinMode(FR, OUTPUT); + digitalWrite(FR, LOW); + //pinMode(BRKMOD, OUTPUT); // this pin not currently exposed + pinMode(PWM, OUTPUT); + stop(); // make sure the motor output pin is not floating initially + + pinMode(RD, INPUT); +} + +/* + * Write the motor direction to the motor direction control or FR pin. + * HIGH = UVW driving sequence (CW) + * LOW = UWV (CCW) + * NOTE: Minimum PWM duty cycle is 10%. + */ +void DRV10970::run(MotorDirection dir, int dc){ + // write direction + digitalWrite(FR, dir); + // write PWM + analogWrite(PWM, dc); +} + +/* + * Stop the motor spindle and send into a low power mode. Exit low power mode + * by driving PWM pin + * NOTE: pwm must be low for at least 1.2ms to enter low power mode + */ +void DRV10970::stop(){ + analogWrite(PWM, LOW); +} + +/* + * Read the RPM of the spindle using the FG pin to measure frequency. + */ +int DRV10970::readRPM(bool debug=false){ + long int t0 = millis(); // read start time + long int cT = millis(); // current time + int gap = 50; // milliseconds to measure for + int toggles = 0; // set number of electrical toggles + int prev_state = digitalRead(FG); // state variable + int cState; + while(cT - t0 < gap){ + cState = digitalRead(FG); // the current state of the FG pin + + if(debug) Serial.println(cState); + + if(prev_state != cState){ // if has toggled, count it + prev_state = cState; + toggles++; + } + cT = millis(); + } + + // TODO: do some math here to figure out the RPM + // probably something like + // toggles gap + + //We are assuming here that 1 "toggle" is equal to 1 full rotation of the spindle. If we record for 1s, you can multiply the + //value we get by 60; which would give us the revolutions per min (RPM). *IN THEORY* + //toggles = toggles*60; + + + return toggles; +} + +/* + * Read the RD pin to determine if the spindle is currently locked (HIGH). + */ +bool DRV10970::spindleFree(){ + return digitalRead(RD) == HIGH; +} diff --git a/lib/DRV10970/src/DRV_10970.h b/lib/DRV10970/src/DRV_10970.h new file mode 100644 index 0000000..c317b03 --- /dev/null +++ b/lib/DRV10970/src/DRV_10970.h @@ -0,0 +1,35 @@ +/**************************************************************** + * Library for interfacing with the DRV 10970 motor driver. + * + * @author: Garrett Wells + * @date: 01/18/22 + * + * Provides a configurable interface for working with the DRV 10970 motor driver. Initially written for University of Idaho senior capstone 2022 for use by the + * Attitude adjustment team working for NASA. + ****************************************************************/ +#ifndef DRV_10970_H +#define DRV_10970_H + +#include + +// default pinout for the SAMD51 +const int DRV_FG = 6, // frequency/rpm indication pin + DRV_FR = 9, // motor direction pin + DRV_BRKMOD = 0, // brake mode (coast/brake), not currently available + DRV_PWM = 10, // pwm output pin + DRV_RD = 5; // lock indication pin + +enum MotorDirection {REV=0, FWD=1}; + +class DRV10970 { + private: + int FG, FR, BRKMOD, PWM, RD; // interface pins + public: + DRV10970(void){} + DRV10970(int fg, int fr, int brkmod, int pwm, int rd); + void run(MotorDirection dir, int dc); // drive motor in direction at dutycycle dc + void stop(); // stop motor driver and put in low power state + int readRPM(bool); // returns the rpm of motor spindle + bool spindleFree(); // returns true if motor spindle is free to spin + }; +#endif diff --git a/lib/FreeRTOS-SAMD51/README.md b/lib/FreeRTOS-SAMD51/README.md new file mode 100644 index 0000000..6718fa8 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/README.md @@ -0,0 +1,43 @@ +### FreeRTOS V10.2.1 for Arduino Samd51 Boards + +#### This library will allow you to create FreeRtos Projects in the arduino IDE and run them on your Samd51 boards. + +Want FreeRtos for the Samd21? Use this other repository +https://github.com/BriscoeTech/Arduino-FreeRTOS-SAMD21 + +*************************************************************************************************************** +#### Tested Boards: + Adafruit Metro M4 Express +*************************************************************************************************************** + +#### Whats new in the recent versions? + +* Added and updated example projects with lessons learned to help you get started setting up a new project. +* Added optional serial printing when the rtos fails, makes tracking down and diagnosing project problems easier. +* Added example project demonstrating the most common rtos failures, and how you might detect them. +* Added example project showing how to change Arduino interrupt priorities to use FreeRtos isr functions. + +*************************************************************************************************************** + +#### Optional Feature: Wrapped Memmory Functions. + +This linker setting change will allow all microcontroller malloc/free/realloc/calloc +operations to be managed by FreeRtos. This could eliminate memory corruption issues on +c++ intensive projects, or projects that might be fragmenting the heap. + +Implementation Guide can be found in: "wrapping memory functions\platform.local.txt" + +*************************************************************************************************************** + +Special thanks to these people for your help and guidance, reference material, and hard work on contributions. + +Richard Barry, for creating FreeRtos and sharing it with the world +www.FreeRtos.org +trlafleur +drewfish +baekgaard +sergiotomasello +godario +TomasRoj +feilipu +greiman \ No newline at end of file diff --git a/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example/Basic_RTOS_Example.ino b/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example/Basic_RTOS_Example.ino new file mode 100644 index 0000000..c964984 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example/Basic_RTOS_Example.ino @@ -0,0 +1,232 @@ +//************************************************************************** +// FreeRtos on Samd51 +// By Scott Briscoe +// +// Project is a simple example of how to get FreeRtos running on a SamD51 processor +// Project can be used as a template to build your projects off of as well +// +//************************************************************************** + +#include + +//************************************************************************** +// Type Defines and Constants +//************************************************************************** + +#define ERROR_LED_PIN 13 //Led Pin: Typical Arduino Board +//#define ERROR_LED_PIN 2 //Led Pin: samd21 xplained board + +#define ERROR_LED_LIGHTUP_STATE HIGH // the state that makes the led light up on your board, either low or high + +// Select the serial port the project should use and communicate over +// Some boards use SerialUSB, some use Serial +//#define SERIAL SerialUSB //Sparkfun Samd51 Boards +#define SERIAL Serial //Adafruit, other Samd51 Boards + +//************************************************************************** +// global variables +//************************************************************************** +TaskHandle_t Handle_aTask; +TaskHandle_t Handle_bTask; +TaskHandle_t Handle_monitorTask; + +//************************************************************************** +// Can use these function for RTOS delays +// Takes into account processor speed +// Use these instead of delay(...) in rtos tasks +//************************************************************************** +void myDelayUs(int us) +{ + vTaskDelay( us / portTICK_PERIOD_US ); +} + +void myDelayMs(int ms) +{ + vTaskDelay( (ms * 1000) / portTICK_PERIOD_US ); +} + +void myDelayMsUntil(TickType_t *previousWakeTime, int ms) +{ + vTaskDelayUntil( previousWakeTime, (ms * 1000) / portTICK_PERIOD_US ); +} + +//***************************************************************** +// Create a thread that prints out A to the screen every two seconds +// this task will delete its self after printing out afew messages +//***************************************************************** +static void threadA( void *pvParameters ) +{ + + SERIAL.println("Thread A: Started"); + for(int x=0; x<100; ++x) + { + SERIAL.print("A"); + SERIAL.flush(); + myDelayMs(500); + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Thread A: Deleting"); + vTaskDelete( NULL ); +} + +//***************************************************************** +// Create a thread that prints out B to the screen every second +// this task will run forever +//***************************************************************** +static void threadB( void *pvParameters ) +{ + SERIAL.println("Thread B: Started"); + + while(1) + { + SERIAL.println("B"); + SERIAL.flush(); + myDelayMs(2000); + } + +} + +//***************************************************************** +// Task will periodically print out useful information about the tasks running +// Is a useful tool to help figure out stack sizes being used +// Run time stats are generated from all task timing collected since startup +// No easy way yet to clear the run time stats yet +//***************************************************************** +static char ptrTaskList[400]; //temporary string buffer for task stats + +void taskMonitor(void *pvParameters) +{ + int x; + int measurement; + + SERIAL.println("Task Monitor: Started"); + + // run this task afew times before exiting forever + while(1) + { + myDelayMs(10000); // print every 10 seconds + + SERIAL.flush(); + SERIAL.println(""); + SERIAL.println("****************************************************"); + SERIAL.print("Free Heap: "); + SERIAL.print(xPortGetFreeHeapSize()); + SERIAL.println(" bytes"); + + SERIAL.print("Min Heap: "); + SERIAL.print(xPortGetMinimumEverFreeHeapSize()); + SERIAL.println(" bytes"); + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task ABS %Util"); + SERIAL.println("****************************************************"); + + vTaskGetRunTimeStats(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task State Prio Stack Num Core" ); + SERIAL.println("****************************************************"); + + vTaskList(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("[Stacks Free Bytes Remaining] "); + + measurement = uxTaskGetStackHighWaterMark( Handle_aTask ); + SERIAL.print("Thread A: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_bTask ); + SERIAL.print("Thread B: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_monitorTask ); + SERIAL.print("Monitor Stack: "); + SERIAL.println(measurement); + + SERIAL.println("****************************************************"); + SERIAL.flush(); + + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Task Monitor: Deleting"); + vTaskDelete( NULL ); + +} + + +//***************************************************************** + +void setup() +{ + + SERIAL.begin(115200); + + delay(1000); // prevents usb driver crash on startup, do not omit this + while (!SERIAL) ; // Wait for serial terminal to open port before starting program + + SERIAL.println(""); + SERIAL.println("******************************"); + SERIAL.println(" Program start "); + SERIAL.println("******************************"); + SERIAL.flush(); + + // Set the led the rtos will blink when we have a fatal rtos error + // RTOS also Needs to know if high/low is the state that turns on the led. + // Error Blink Codes: + // 3 blinks - Fatal Rtos Error, something bad happened. Think really hard about what you just changed. + // 2 blinks - Malloc Failed, Happens when you couldn't create a rtos object. + // Probably ran out of heap. + // 1 blink - Stack overflow, Task needs more bytes defined for its stack! + // Use the taskMonitor thread to help gauge how much more you need + vSetErrorLed(ERROR_LED_PIN, ERROR_LED_LIGHTUP_STATE); + + // sets the serial port to print errors to when the rtos crashes + // if this is not set, serial information is not printed by default + vSetErrorSerial(&SERIAL); + + // Create the threads that will be managed by the rtos + // Sets the stack size and priority of each task + // Also initializes a handler pointer to each task, which are important to communicate with and retrieve info from tasks + xTaskCreate(threadA, "Task A", 256, NULL, tskIDLE_PRIORITY + 3, &Handle_aTask); + xTaskCreate(threadB, "Task B", 256, NULL, tskIDLE_PRIORITY + 2, &Handle_bTask); + xTaskCreate(taskMonitor, "Task Monitor", 256, NULL, tskIDLE_PRIORITY + 1, &Handle_monitorTask); + + // Start the RTOS, this function will never return and will schedule the tasks. + vTaskStartScheduler(); + + // error scheduler failed to start + // should never get here + while(1) + { + SERIAL.println("Scheduler Failed! \n"); + SERIAL.flush(); + delay(1000); + } + +} + +//***************************************************************** +// This is now the rtos idle loop +// No rtos blocking functions allowed! +//***************************************************************** +void loop() +{ + // Optional commands, can comment/uncomment below + SERIAL.print("."); //print out dots in terminal, we only do this when the RTOS is in the idle state + SERIAL.flush(); + delay(100); //delay is interrupt friendly, unlike vNopDelayMS +} + + +//***************************************************************** + diff --git a/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example2/Basic_RTOS_Example2.ino b/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example2/Basic_RTOS_Example2.ino new file mode 100644 index 0000000..0b0aeb4 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/Basic_RTOS_Example2/Basic_RTOS_Example2.ino @@ -0,0 +1,261 @@ +//************************************************************************** +// FreeRtos on Samd51 +// By Scott Briscoe +// +// Project is a simple example of how to get FreeRtos running on a SamD51 processor +// Project can be used as a template to build your projects off of as well +// +// This example uses the MemoryFree library by mpflaga, to show how much ram is being used by the rtos and all global objects +// https://github.com/mpflaga/Arduino-MemoryFree +//************************************************************************** + +#include //samd51 +#include + +//************************************************************************** +// Type Defines and Constants +//************************************************************************** + +#define ERROR_LED_PIN 13 //Led Pin: Typical Arduino Board +//#define ERROR_LED_PIN 2 //Led Pin: samd21 xplained board + +#define ERROR_LED_LIGHTUP_STATE HIGH // the state that makes the led light up on your board, either low or high + +#define DEVICE_TOTAL_RAM 192000 // bytes of ram for this processor + +// Select the serial port the project should use and communicate over +// Some boards use SerialUSB, some use Serial +//#define SERIAL SerialUSB //Sparkfun Samd21 Boards +#define SERIAL Serial //Adafruit, other Samd21 Boards + +//************************************************************************** +// global variables +//************************************************************************** +TaskHandle_t Handle_aTask; +TaskHandle_t Handle_bTask; +TaskHandle_t Handle_monitorTask; + +//************************************************************************** +// Can use these function for RTOS delays +// Takes into account processor speed +// Use these instead of delay(...) in rtos tasks +//************************************************************************** +void myDelayUs(int us) +{ + vTaskDelay( us / portTICK_PERIOD_US ); +} + +void myDelayMs(int ms) +{ + vTaskDelay( (ms * 1000) / portTICK_PERIOD_US ); +} + +void myDelayMsUntil(TickType_t *previousWakeTime, int ms) +{ + vTaskDelayUntil( previousWakeTime, (ms * 1000) / portTICK_PERIOD_US ); +} + +//************************************************************************** +// Print how much ram is free on the device +// Useful to see how much ram is available at startup with current heap size settings, and after initializing all classes +// freeMemory() gives wrong answers after starting the rtos for unknown reasons, only use before rtos start +//************************************************************************** +void printRamFree() +{ + SERIAL.print("Ram Remaining : ("); + SERIAL.print( freeMemory() ); + SERIAL.print(" / "); + SERIAL.print(DEVICE_TOTAL_RAM); + SERIAL.print(") bytes "); + double percentage = ((double)freeMemory() / (double)DEVICE_TOTAL_RAM) * 100; + SERIAL.print( percentage ); + SERIAL.println("%"); + SERIAL.flush(); +} + +//***************************************************************** +// Create a thread that prints out A to the screen every two seconds +// this task will delete its self after printing out afew messages +//***************************************************************** +static void threadA( void *pvParameters ) +{ + + SERIAL.println("Thread A: Started"); + for(int x=0; x<20; ++x) + { + SERIAL.print("A"); + SERIAL.flush(); + myDelayMs(500); + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Thread A: Deleting"); + vTaskDelete( NULL ); +} + +//***************************************************************** +// Create a thread that prints out B to the screen every second +// this task will run forever +//***************************************************************** +static void threadB( void *pvParameters ) +{ + SERIAL.println("Thread B: Started"); + + while(1) + { + SERIAL.println("B"); + SERIAL.flush(); + myDelayMs(2000); + } + +} + +//***************************************************************** +// Task will periodically print out useful information about the tasks running +// Is a useful tool to help figure out stack sizes being used +// Run time stats are generated from all task timing collected since startup +// No easy way yet to clear the run time stats yet +//***************************************************************** +static char ptrTaskList[400]; //temporary string buffer for task stats + +void taskMonitor(void *pvParameters) +{ + int x; + int measurement; + + SERIAL.println("Task Monitor: Started"); + + // run this task afew times before exiting forever + for(x=0; x<10; ++x) + { + + SERIAL.flush(); + SERIAL.println(""); + SERIAL.println("****************************************************"); + SERIAL.print("Free Heap: "); + SERIAL.print(xPortGetFreeHeapSize()); + SERIAL.println(" bytes"); + + SERIAL.print("Min Heap: "); + SERIAL.print(xPortGetMinimumEverFreeHeapSize()); + SERIAL.println(" bytes"); + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task ABS %Util"); + SERIAL.println("****************************************************"); + + vTaskGetRunTimeStats(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task State Prio Stack Num Core" ); + SERIAL.println("****************************************************"); + + vTaskList(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("[Stacks Free Bytes Remaining] "); + + measurement = uxTaskGetStackHighWaterMark( Handle_aTask ); + SERIAL.print("Thread A: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_bTask ); + SERIAL.print("Thread B: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_monitorTask ); + SERIAL.print("Monitor Stack: "); + SERIAL.println(measurement); + + SERIAL.println("****************************************************"); + SERIAL.flush(); + + myDelayMs(10000); // print every 10 seconds + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Task Monitor: Deleting"); + vTaskDelete( NULL ); + +} + + +//***************************************************************** + +void setup() +{ + + SERIAL.begin(115200); + + delay(1000); // prevents usb driver crash on startup, do not omit this + while (!SERIAL) ; // Wait for serial terminal to open port before starting program + + // show the amount of ram free at startup + printRamFree(); + + SERIAL.println(""); + SERIAL.println("******************************"); + SERIAL.println(" Program start "); + SERIAL.println("******************************"); + SERIAL.flush(); + + // Set the led the rtos will blink when we have a fatal rtos error + // RTOS also Needs to know if high/low is the state that turns on the led. + // Error Blink Codes: + // 3 blinks - Fatal Rtos Error, something bad happened. Think really hard about what you just changed. + // 2 blinks - Malloc Failed, Happens when you couldn't create a rtos object. + // Probably ran out of heap. + // 1 blink - Stack overflow, Task needs more bytes defined for its stack! + // Use the taskMonitor thread to help gauge how much more you need + vSetErrorLed(ERROR_LED_PIN, ERROR_LED_LIGHTUP_STATE); + + // sets the serial port to print errors to when the rtos crashes + // if this is not set, serial information is not printed by default + vSetErrorSerial(&SERIAL); + + // Create the threads that will be managed by the rtos + // Sets the stack size and priority of each task + // Also initializes a handler pointer to each task, which are important to communicate with and retrieve info from tasks + xTaskCreate(threadA, "Task A", 256, NULL, tskIDLE_PRIORITY + 3, &Handle_aTask); + xTaskCreate(threadB, "Task B", 256, NULL, tskIDLE_PRIORITY + 2, &Handle_bTask); + xTaskCreate(taskMonitor, "Task Monitor", 256, NULL, tskIDLE_PRIORITY + 1, &Handle_monitorTask); + + // show the amount of ram free after initializations + printRamFree(); + + // Start the RTOS, this function will never return and will schedule the tasks. + vTaskStartScheduler(); + + // error scheduler failed to start + // should never get here + while(1) + { + SERIAL.println("Scheduler Failed! \n"); + SERIAL.flush(); + delay(1000); + } + +} + +//***************************************************************** +// This is now the rtos idle loop +// No rtos blocking functions allowed! +//***************************************************************** +void loop() +{ + // Optional commands, can comment/uncomment below + SERIAL.print("."); //print out dots in terminal, we only do this when the RTOS is in the idle state + SERIAL.flush(); + delay(100); //delay is interrupt friendly, unlike vNopDelayMS +} + + +//***************************************************************** + diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/CompilerAndLinker_Test.ino b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/CompilerAndLinker_Test.ino new file mode 100644 index 0000000..7aac331 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/CompilerAndLinker_Test.ino @@ -0,0 +1,28 @@ + +// External Libraries +#include //samd51 + +#include "GameMessage.h" +#include "GameData.h" +#include "GameThing.c" + + +// This example project tests that a .ino, c header, or cpp header can include and compile the library +// Keeping this example around to make sure that any library architecture changes will still compile in a arduino project +// Found a obscure compiling error that would occur if the librarys header file did not include the arduino library explicitly +// Also useful to make sure rtos C code is not trying to include Cpp arduino functions + + +//************************************************************************** +void setup() +{ + +} + + +//************************************************************************** +void loop() +{ + +} + diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.cpp b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.cpp new file mode 100644 index 0000000..468d45e --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.cpp @@ -0,0 +1,2 @@ +#include "GameData.h" // include this classes header file + diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.h b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.h new file mode 100644 index 0000000..0730b9d --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameData.h @@ -0,0 +1,11 @@ +#include //samd51 + + +#ifndef GAME_DATA_H +#define GAME_DATA_H + + + + +#endif + diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.cpp b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.cpp new file mode 100644 index 0000000..529c69b --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.cpp @@ -0,0 +1,4 @@ +#include "GameMessage.h" // include this classes header file + + + diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.h b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.h new file mode 100644 index 0000000..1d8121c --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameMessage.h @@ -0,0 +1,13 @@ + +// include the other header files to make this class work +#include //samd51 +#include "GameData.h" + + +#ifndef GAME_MESSAGE_H +#define GAME_MESSAGE_H + + + + +#endif diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.c b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.c new file mode 100644 index 0000000..ab8aba0 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.c @@ -0,0 +1 @@ +#include "GameThing.h" // include this files header file diff --git a/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.h b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.h new file mode 100644 index 0000000..4382f37 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/CompilerAndLinker_Test/GameThing.h @@ -0,0 +1,10 @@ +#include //samd51 + +#ifndef GAME_THING_H +#define GAME_THING_H + + + + +#endif + diff --git a/lib/FreeRTOS-SAMD51/examples/GpioInterrupt_Test/GpioInterrupt_Test.ino b/lib/FreeRTOS-SAMD51/examples/GpioInterrupt_Test/GpioInterrupt_Test.ino new file mode 100644 index 0000000..e6aa7b1 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/GpioInterrupt_Test/GpioInterrupt_Test.ino @@ -0,0 +1,278 @@ +//************************************************************************** +// FreeRtos on Samd51 +// By Scott Briscoe +// +// Project is a simple example of how to get FreeRtos running on a SamD51 processor +// Project can be used as a template to build your projects off of as well +// +// This projects sets up a external gpio interrupt to send task messages to a task +// +//************************************************************************** + +#include + +//************************************************************************** +// Type Defines and Constants +//************************************************************************** + +#define ERROR_LED_PIN 13 //Led Pin: Typical Arduino Board +//#define ERROR_LED_PIN 2 //Led Pin: samd21 xplained board + +#define BUTTON_PIN 9 +#define BUTTON_PIN_IRQ EIC_4_IRQn //irq number for pin 9 interrupt. Refer to samd51j19a.h and variant.cpp to find correct enum + +#define ERROR_LED_LIGHTUP_STATE HIGH // the state that makes the led light up on your board, either low or high + +// Select the serial port the project should use and communicate over +// Some boards use SerialUSB, some use Serial +//#define SERIAL SerialUSB //Sparkfun Samd51 Boards +#define SERIAL Serial //Adafruit, other Samd51 Boards + +//************************************************************************** +// global variables +//************************************************************************** +TaskHandle_t Handle_aTask; +TaskHandle_t Handle_bTask; +TaskHandle_t Handle_monitorTask; + +//************************************************************************** +// Can use these function for RTOS delays +// Takes into account processor speed +// Use these instead of delay(...) in rtos tasks +//************************************************************************** +void myDelayUs(int us) +{ + vTaskDelay( us / portTICK_PERIOD_US ); +} + +void myDelayMs(int ms) +{ + vTaskDelay( (ms * 1000) / portTICK_PERIOD_US ); +} + +void myDelayMsUntil(TickType_t *previousWakeTime, int ms) +{ + vTaskDelayUntil( previousWakeTime, (ms * 1000) / portTICK_PERIOD_US ); +} + +//***************************************************************** +// Create a thread that prints out A to the screen +//***************************************************************** +static void threadA( void *pvParameters ) +{ + + SERIAL.println("Thread A: Started"); + while(1) + { + SERIAL.println("A"); + SERIAL.flush(); + myDelayMs(2000); + } +} + +//************************************************************************** +// interrupt handler function +//************************************************************************** + +//#define ENABLE_DEBUG_OUTPUT_ISR + +void Interrupt_MyHandler_IRQ() +{ + + #ifdef ENABLE_DEBUG_OUTPUT_ISR + SERIAL.print(F("[")); + #endif + + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + + // release task to handle the radios read data + vTaskNotifyGiveFromISR( Handle_bTask, &xHigherPriorityTaskWoken ); + portYIELD_FROM_ISR( xHigherPriorityTaskWoken ); + + #ifdef ENABLE_DEBUG_OUTPUT_ISR + SERIAL.print(F("]")); + SERIAL.flush(); + #endif + +} + +//***************************************************************** +// Create a thread that prints out B when we receive a gpio interrupt +// this task will run forever +//***************************************************************** + +#include "wiring_private.h" //for NVIC_SetPriority function + +static void threadB( void *pvParameters ) +{ + SERIAL.println("Thread B: Started"); + + // setup the hardware as a input to listen to + pinMode(BUTTON_PIN, INPUT_PULLUP); + attachInterrupt( BUTTON_PIN, Interrupt_MyHandler_IRQ, FALLING ); + + // change the interrupt priority, this is required to prevent freertos assert and rtos problems + // https://www.freertos.org/RTOS-Cortex-M3-M4.html + // arduino default priority is zero, and freertos does not allow zero priority interrupts to use isr messages + // do this after attaching interrupt + NVIC_SetPriority(BUTTON_PIN_IRQ, configLIBRARY_LOWEST_INTERRUPT_PRIORITY); + + while(1) + { + + // wait for a interrupt to release the task + while (ulTaskNotifyTake( pdTRUE, portMAX_DELAY ) != pdPASS) + { + // do nothing + } + + SERIAL.print("B"); + SERIAL.flush(); + + //myDelayMs(200); // help debounce the interrupt handling + } + +} + +//***************************************************************** +// Task will periodically print out useful information about the tasks running +// Is a useful tool to help figure out stack sizes being used +// Run time stats are generated from all task timing collected since startup +// No easy way yet to clear the run time stats yet +//***************************************************************** +static char ptrTaskList[400]; //temporary string buffer for task stats + +void taskMonitor(void *pvParameters) +{ + int x; + int measurement; + + SERIAL.println("Task Monitor: Started"); + + // run this task afew times before exiting forever + while(1) + { + myDelayMs(10000); // print every 10 seconds + + SERIAL.flush(); + SERIAL.println(""); + SERIAL.println("****************************************************"); + SERIAL.print("Free Heap: "); + SERIAL.print(xPortGetFreeHeapSize()); + SERIAL.println(" bytes"); + + SERIAL.print("Min Heap: "); + SERIAL.print(xPortGetMinimumEverFreeHeapSize()); + SERIAL.println(" bytes"); + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task ABS %Util"); + SERIAL.println("****************************************************"); + + vTaskGetRunTimeStats(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task State Prio Stack Num Core" ); + SERIAL.println("****************************************************"); + + vTaskList(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("[Stacks Free Bytes Remaining] "); + + measurement = uxTaskGetStackHighWaterMark( Handle_aTask ); + SERIAL.print("Thread A: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_bTask ); + SERIAL.print("Thread B: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_monitorTask ); + SERIAL.print("Monitor Stack: "); + SERIAL.println(measurement); + + SERIAL.println("****************************************************"); + SERIAL.flush(); + + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Task Monitor: Deleting"); + vTaskDelete( NULL ); + +} + + +//***************************************************************** + +void setup() +{ + + SERIAL.begin(115200); + + delay(1000); // prevents usb driver crash on startup, do not omit this + while (!SERIAL) ; // Wait for serial terminal to open port before starting program + + SERIAL.println(""); + SERIAL.println("******************************"); + SERIAL.println(" Program start "); + SERIAL.println("******************************"); + SERIAL.flush(); + + // Set the led the rtos will blink when we have a fatal rtos error + // RTOS also Needs to know if high/low is the state that turns on the led. + // Error Blink Codes: + // 3 blinks - Fatal Rtos Error, something bad happened. Think really hard about what you just changed. + // 2 blinks - Malloc Failed, Happens when you couldn't create a rtos object. + // Probably ran out of heap. + // 1 blink - Stack overflow, Task needs more bytes defined for its stack! + // Use the taskMonitor thread to help gauge how much more you need + vSetErrorLed(ERROR_LED_PIN, ERROR_LED_LIGHTUP_STATE); + + // sets the serial port to print errors to when the rtos crashes + // if this is not set, serial information is not printed by default + vSetErrorSerial(&SERIAL); + + // Create the threads that will be managed by the rtos + // Sets the stack size and priority of each task + // Also initializes a handler pointer to each task, which are important to communicate with and retrieve info from tasks + xTaskCreate(threadA, "Task A", 256, NULL, tskIDLE_PRIORITY + 3, &Handle_aTask); + xTaskCreate(threadB, "Task B", 256, NULL, tskIDLE_PRIORITY + 2, &Handle_bTask); + xTaskCreate(taskMonitor, "Task Monitor", 256, NULL, tskIDLE_PRIORITY + 1, &Handle_monitorTask); + + // Start the RTOS, this function will never return and will schedule the tasks. + vTaskStartScheduler(); + + // error scheduler failed to start + // should never get here + while(1) + { + SERIAL.println("Scheduler Failed! \n"); + SERIAL.flush(); + delay(1000); + } + +} + +//***************************************************************** +// This is now the rtos idle loop +// No rtos blocking functions allowed! +//***************************************************************** +void loop() +{ + // Optional commands, can comment/uncomment below + SERIAL.print("."); //print out dots in terminal, we only do this when the RTOS is in the idle state + SERIAL.flush(); + delay(100); //delay is interrupt friendly, unlike vNopDelayMS +} + + +//***************************************************************** + diff --git a/lib/FreeRTOS-SAMD51/examples/RtosCrash_Test/RtosCrash_Test.ino b/lib/FreeRTOS-SAMD51/examples/RtosCrash_Test/RtosCrash_Test.ino new file mode 100644 index 0000000..c775ad4 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/examples/RtosCrash_Test/RtosCrash_Test.ino @@ -0,0 +1,331 @@ +//************************************************************************** +// FreeRtos on Samd51 +// By Scott Briscoe +// +// Project is a simple test to make sure the different rtos failure detections +// are caught and the error led to blink properly. +// +// A great demo to also explore the common reasons the rtos crashes and how +// to avoid them +// +//************************************************************************** + +#include + +//************************************************************************** +// Type Defines and Constants +//************************************************************************** + +// change this to cause different errors to be compiled and run +#define ERROR_CHECKING 2 //0 for off, 1-6 to select failure mode to compile + + +#define ERROR_LED_PIN 13 //Led Pin: Typical Arduino Board +//#define ERROR_LED_PIN 2 //Led Pin: samd21 xplained board + +#define ERROR_LED_LIGHTUP_STATE HIGH // the state that makes the led light up on your board, either low or high + +// Select the serial port the project should use and communicate over +// Some boards use SerialUSB, some use Serial +//#define SERIAL SerialUSB //Sparkfun Samd51 Boards +#define SERIAL Serial //Adafruit, other Samd51 Boards + +//************************************************************************** +// global variables +//************************************************************************** +TaskHandle_t Handle_aTask; +TaskHandle_t Handle_bTask; +TaskHandle_t Handle_monitorTask; + +//************************************************************************** +// Can use these function for RTOS delays +// Takes into account processor speed +// Use these instead of delay(...) in rtos tasks +//************************************************************************** +void myDelayUs(int us) +{ + vTaskDelay( us / portTICK_PERIOD_US ); +} + +void myDelayMs(int ms) +{ + vTaskDelay( (ms * 1000) / portTICK_PERIOD_US ); +} + +void myDelayMsUntil(TickType_t *previousWakeTime, int ms) +{ + vTaskDelayUntil( previousWakeTime, (ms * 1000) / portTICK_PERIOD_US ); +} + + +#if ERROR_CHECKING == 2 +void endlessRecursion(int l) +{ + int a[l]; + long sum = 0; + + for(int x=0; x + +//************************************************************************** +// Type Defines and Constants +//************************************************************************** + +#define ERROR_LED_PIN 13 //Led Pin: Typical Arduino Board +//#define ERROR_LED_PIN 2 //Led Pin: samd21 xplained board + +#define ERROR_LED_LIGHTUP_STATE HIGH // the state that makes the led light up on your board, either low or high + +// Select the serial port the project should use and communicate over +// Some boards use SerialUSB, some use Serial +//#define SERIAL SerialUSB //Sparkfun Samd51 Boards +#define SERIAL Serial //Adafruit, other Samd51 Boards + +//************************************************************************** +// global variables +//************************************************************************** +TaskHandle_t Handle_aTask; +TaskHandle_t Handle_bTask; +TaskHandle_t Handle_cTask; +TaskHandle_t Handle_monitorTask; + +//************************************************************************** +// Can use these function for RTOS delays +// Takes into account processor speed +// Use these instead of delay(...) in rtos tasks +//************************************************************************** +void myDelayUs(int us) +{ + vTaskDelay( us / portTICK_PERIOD_US ); +} + +void myDelayMs(int ms) +{ + vTaskDelay( (ms * 1000) / portTICK_PERIOD_US ); +} + +void myDelayMsUntil(TickType_t *previousWakeTime, int ms) +{ + vTaskDelayUntil( previousWakeTime, (ms * 1000) / portTICK_PERIOD_US ); +} + +//***************************************************************** +// Create a thread that prints out A to the screen every two seconds +// this task will delete its self after printing out afew messages +//***************************************************************** +static void threadA( void *pvParameters ) +{ + + SERIAL.println("Thread A: Started"); + for(int x=0; x<100; ++x) + { + SERIAL.print("A"); + SERIAL.flush(); + myDelayMs(500); + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Thread A: Deleting"); + vTaskDelete( NULL ); +} + +//***************************************************************** +// Create a thread that prints out B to the screen every second +// this task will run forever +//***************************************************************** +static void threadB( void *pvParameters ) +{ + SERIAL.println("Thread B: Started"); + + while(1) + { + SERIAL.println("B"); + SERIAL.flush(); + myDelayMs(2000); + } + +} + +//***************************************************************** +// Create a thread that just crunches alot of numbers +// This thread should eat up a noticeable amount of processor time +// this task will run forever +//***************************************************************** +volatile double variable; +static void threadC( void *pvParameters ) +{ + + // Initialize the xLastWakeTime variable with the current time. + TickType_t lastWakeTime = xTaskGetTickCount(); + + SERIAL.println("Thread C: Started"); + + while(1) + { + SERIAL.print("C"); + SERIAL.flush(); + + // do some complicated math to fill up period + // creates a duty cycle of processing + for(long x=0; x<(50*32000); ++x) + { + variable *= PI; + } + + // will sleep for the rest of this period window + myDelayMsUntil(&lastWakeTime, 3100); + } + +} + +//***************************************************************** +// Task will periodically print out useful information about the tasks running +// Is a useful tool to help figure out stack sizes being used +// Run time stats are generated from all task timing collected since startup +// No easy way yet to clear the run time stats yet +//***************************************************************** +static char ptrTaskList[400]; //temporary string buffer for task stats + +void taskMonitor(void *pvParameters) +{ + int x; + int measurement; + + SERIAL.println("Task Monitor: Started"); + + // run this task afew times before exiting forever + while(1) + { + myDelayMs(10000); // print every 10 seconds + + SERIAL.flush(); + SERIAL.println(""); + SERIAL.println("****************************************************"); + SERIAL.print("Free Heap: "); + SERIAL.print(xPortGetFreeHeapSize()); + SERIAL.println(" bytes"); + + SERIAL.print("Min Heap: "); + SERIAL.print(xPortGetMinimumEverFreeHeapSize()); + SERIAL.println(" bytes"); + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task ABS %Util"); + SERIAL.println("****************************************************"); + + vTaskGetRunTimeStats(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("Task State Prio Stack Num Core" ); + SERIAL.println("****************************************************"); + + vTaskList(ptrTaskList); //save stats to char array + SERIAL.println(ptrTaskList); //prints out already formatted stats + SERIAL.flush(); + + SERIAL.println("****************************************************"); + SERIAL.println("[Stacks Free Bytes Remaining] "); + + measurement = uxTaskGetStackHighWaterMark( Handle_aTask ); + SERIAL.print("Thread A: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_bTask ); + SERIAL.print("Thread B: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_cTask ); + SERIAL.print("Thread C: "); + SERIAL.println(measurement); + + measurement = uxTaskGetStackHighWaterMark( Handle_monitorTask ); + SERIAL.print("Monitor Stack: "); + SERIAL.println(measurement); + + SERIAL.println("****************************************************"); + SERIAL.flush(); + + } + + // delete ourselves. + // Have to call this or the system crashes when you reach the end bracket and then get scheduled. + SERIAL.println("Task Monitor: Deleting"); + vTaskDelete( NULL ); + +} + + +//***************************************************************** + +void setup() +{ + + SERIAL.begin(115200); + + delay(1000); // prevents usb driver crash on startup, do not omit this + while (!SERIAL) ; // Wait for serial terminal to open port before starting program + + SERIAL.println(""); + SERIAL.println("******************************"); + SERIAL.println(" Program start "); + SERIAL.println("******************************"); + SERIAL.flush(); + + // Set the led the rtos will blink when we have a fatal rtos error + // RTOS also Needs to know if high/low is the state that turns on the led. + // Error Blink Codes: + // 3 blinks - Fatal Rtos Error, something bad happened. Think really hard about what you just changed. + // 2 blinks - Malloc Failed, Happens when you couldn't create a rtos object. + // Probably ran out of heap. + // 1 blink - Stack overflow, Task needs more bytes defined for its stack! + // Use the taskMonitor thread to help gauge how much more you need + vSetErrorLed(ERROR_LED_PIN, ERROR_LED_LIGHTUP_STATE); + + // sets the serial port to print errors to when the rtos crashes + // if this is not set, serial information is not printed by default + vSetErrorSerial(&SERIAL); + + // Create the threads that will be managed by the rtos + // Sets the stack size and priority of each task + // Also initializes a handler pointer to each task, which are important to communicate with and retrieve info from tasks + xTaskCreate(threadA, "Task A", 256, NULL, tskIDLE_PRIORITY + 4, &Handle_aTask); + xTaskCreate(threadB, "Task B", 256, NULL, tskIDLE_PRIORITY + 3, &Handle_bTask); + xTaskCreate(threadC, "Task C", 256, NULL, tskIDLE_PRIORITY + 2, &Handle_cTask); + xTaskCreate(taskMonitor, "Task Monitor", 256, NULL, tskIDLE_PRIORITY + 1, &Handle_monitorTask); + + // Start the RTOS, this function will never return and will schedule the tasks. + vTaskStartScheduler(); + + // error scheduler failed to start + // should never get here + while(1) + { + SERIAL.println("Scheduler Failed! \n"); + SERIAL.flush(); + delay(1000); + } + +} + +//***************************************************************** +// This is now the rtos idle loop +// No rtos blocking functions allowed! +//***************************************************************** +void loop() +{ + // Optional commands, can comment/uncomment below + SERIAL.print("."); //print out dots in terminal, we only do this when the RTOS is in the idle state + SERIAL.flush(); + delay(100); //delay is interrupt friendly, unlike vNopDelayMS +} + + +//***************************************************************** + diff --git a/lib/FreeRTOS-SAMD51/library.properties b/lib/FreeRTOS-SAMD51/library.properties new file mode 100644 index 0000000..672cb9d --- /dev/null +++ b/lib/FreeRTOS-SAMD51/library.properties @@ -0,0 +1,10 @@ +name=FreeRTOS_SAMD51 +version=1.3.0 +author=BriscoeTech <> +maintainer=BriscoeTech <> +sentence=FreeRTOS ported for Arduino SAMD51 processors +paragraph=FreeRTOS ported for Arduino SAMD51 processors +category=Device Control +url=https://github.com/BriscoeTech/Arduino-FreeRTOS-SAMD51 +architectures=samd +repository=https://github.com/BriscoeTech/Arduino-FreeRTOS-SAMD51.git diff --git a/lib/FreeRTOS-SAMD51/src/FreeRTOS.h b/lib/FreeRTOS-SAMD51/src/FreeRTOS.h new file mode 100644 index 0000000..d6affa9 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/FreeRTOS.h @@ -0,0 +1,1281 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* + * If stdint.h cannot be located then: + * + If using GCC ensure the -nostdint options is *not* being used. + * + Ensure the project's include path includes the directory in which your + * compiler stores stdint.h. + * + Set any compiler options necessary for it to support C99, as technically + * stdint.h is only mandatory with C99 (FreeRTOS does not require C99 in any + * other way). + * + The FreeRTOS download includes a simple stdint.h definition that can be + * used in cases where none is provided by the compiler. The files only + * contains the typedefs required to build FreeRTOS. Read the instructions + * in FreeRTOS/source/stdint.readme for more information. + */ +#include /* READ COMMENT ABOVE. */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + +/* Must be defaulted before configUSE_NEWLIB_REENTRANT is used below. */ +#ifndef configUSE_NEWLIB_REENTRANT + #define configUSE_NEWLIB_REENTRANT 0 +#endif + +/* Required if struct _reent is used. */ +#if ( configUSE_NEWLIB_REENTRANT == 1 ) + #include +#endif +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configMINIMAL_STACK_SIZE + #error Missing definition: configMINIMAL_STACK_SIZE must be defined in FreeRTOSConfig.h. configMINIMAL_STACK_SIZE defines the size (in words) of the stack allocated to the idle task. Refer to the demo project provided for your port for a suitable value. +#endif + +#ifndef configMAX_PRIORITIES + #error Missing definition: configMAX_PRIORITIES must be defined in FreeRTOSConfig.h. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#if configMAX_PRIORITIES < 1 + #error configMAX_PRIORITIES must be defined to be greater than or equal to 1. +#endif + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS must be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #define configUSE_CO_ROUTINES 0 +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #define INCLUDE_vTaskPrioritySet 0 +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #define INCLUDE_uxTaskPriorityGet 0 +#endif + +#ifndef INCLUDE_vTaskDelete + #define INCLUDE_vTaskDelete 0 +#endif + +#ifndef INCLUDE_vTaskSuspend + #define INCLUDE_vTaskSuspend 0 +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #define INCLUDE_vTaskDelayUntil 0 +#endif + +#ifndef INCLUDE_vTaskDelay + #define INCLUDE_vTaskDelay 0 +#endif + +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTaskAbortDelay + #define INCLUDE_xTaskAbortDelay 0 +#endif + +#ifndef INCLUDE_xQueueGetMutexHolder + #define INCLUDE_xQueueGetMutexHolder 0 +#endif + +#ifndef INCLUDE_xSemaphoreGetMutexHolder + #define INCLUDE_xSemaphoreGetMutexHolder INCLUDE_xQueueGetMutexHolder +#endif + +#ifndef INCLUDE_xTaskGetHandle + #define INCLUDE_xTaskGetHandle 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark2 + #define INCLUDE_uxTaskGetStackHighWaterMark2 0 +#endif + +#ifndef INCLUDE_eTaskGetState + #define INCLUDE_eTaskGetState 0 +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef INCLUDE_xTimerPendFunctionCall + #define INCLUDE_xTimerPendFunctionCall 0 +#endif + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + +#if configUSE_CO_ROUTINES != 0 + #ifndef configMAX_CO_ROUTINE_PRIORITIES + #error configMAX_CO_ROUTINE_PRIORITIES must be greater than or equal to 1. + #endif +#endif + +#ifndef configUSE_DAEMON_TASK_STARTUP_HOOK + #define configUSE_DAEMON_TASK_STARTUP_HOOK 0 +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef configNUM_THREAD_LOCAL_STORAGE_POINTERS + #define configNUM_THREAD_LOCAL_STORAGE_POINTERS 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef configASSERT + #define configASSERT( x ) + #define configASSERT_DEFINED 0 +#else + #define configASSERT_DEFINED 1 +#endif + +#ifndef portMEMORY_BARRIER + #define portMEMORY_BARRIER() +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + +#ifndef portCLEAN_UP_TCB + #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef portPRE_TASK_DELETE_HOOK + #define portPRE_TASK_DELETE_HOOK( pvTaskToDelete, pxYieldPending ) +#endif + +#ifndef portSETUP_TCB + #define portSETUP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1 ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) + #define pcQueueGetName( xQueue ) +#endif + +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE uint32_t +#endif + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceINCREASE_TICK_COUNT + /* Called before stepping the tick count after waking from tickless idle + sleep. */ + #define traceINCREASE_TICK_COUNT( x ) +#endif + +#ifndef traceLOW_POWER_IDLE_BEGIN + /* Called immediately before entering tickless idle. */ + #define traceLOW_POWER_IDLE_BEGIN() +#endif + +#ifndef traceLOW_POWER_IDLE_END + /* Called when returning to the Idle task after a tickless idle. */ + #define traceLOW_POWER_IDLE_END() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceTASK_PRIORITY_INHERIT + /* Called when a task attempts to take a mutex that is already held by a + lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task + that holds the mutex. uxInheritedPriority is the priority the mutex holder + will inherit (the priority of the task that is attempting to obtain the + muted. */ + #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) +#endif + +#ifndef traceTASK_PRIORITY_DISINHERIT + /* Called when a task releases a mutex, the holding of which had resulted in + the task inheriting the priority of a higher priority task. + pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the + mutex. uxOriginalPriority is the task's configured (base) priority. */ + #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_PEEK + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +#ifndef configRECORD_STACK_HIGH_ADDRESS + #define configRECORD_STACK_HIGH_ADDRESS 0 +#endif + +#ifndef configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H + #define configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceMOVED_TASK_TO_READY_STATE + #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef tracePOST_MOVED_TASK_TO_READY_STATE + #define tracePOST_MOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED( ucQueueType ) +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FAILED + #define traceQUEUE_PEEK_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FROM_ISR + #define traceQUEUE_PEEK_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK_FROM_ISR_FAILED + #define traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL( x ) +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef traceMALLOC + #define traceMALLOC( pvAddress, uiSize ) +#endif + +#ifndef traceFREE + #define traceFREE( pvAddress, uiSize ) +#endif + +#ifndef traceEVENT_GROUP_CREATE + #define traceEVENT_GROUP_CREATE( xEventGroup ) +#endif + +#ifndef traceEVENT_GROUP_CREATE_FAILED + #define traceEVENT_GROUP_CREATE_FAILED() +#endif + +#ifndef traceEVENT_GROUP_SYNC_BLOCK + #define traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor ) +#endif + +#ifndef traceEVENT_GROUP_SYNC_END + #define traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred +#endif + +#ifndef traceEVENT_GROUP_WAIT_BITS_BLOCK + #define traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor ) +#endif + +#ifndef traceEVENT_GROUP_WAIT_BITS_END + #define traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred +#endif + +#ifndef traceEVENT_GROUP_CLEAR_BITS + #define traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear ) +#endif + +#ifndef traceEVENT_GROUP_CLEAR_BITS_FROM_ISR + #define traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear ) +#endif + +#ifndef traceEVENT_GROUP_SET_BITS + #define traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet ) +#endif + +#ifndef traceEVENT_GROUP_SET_BITS_FROM_ISR + #define traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet ) +#endif + +#ifndef traceEVENT_GROUP_DELETE + #define traceEVENT_GROUP_DELETE( xEventGroup ) +#endif + +#ifndef tracePEND_FUNC_CALL + #define tracePEND_FUNC_CALL(xFunctionToPend, pvParameter1, ulParameter2, ret) +#endif + +#ifndef tracePEND_FUNC_CALL_FROM_ISR + #define tracePEND_FUNC_CALL_FROM_ISR(xFunctionToPend, pvParameter1, ulParameter2, ret) +#endif + +#ifndef traceQUEUE_REGISTRY_ADD + #define traceQUEUE_REGISTRY_ADD(xQueue, pcQueueName) +#endif + +#ifndef traceTASK_NOTIFY_TAKE_BLOCK + #define traceTASK_NOTIFY_TAKE_BLOCK() +#endif + +#ifndef traceTASK_NOTIFY_TAKE + #define traceTASK_NOTIFY_TAKE() +#endif + +#ifndef traceTASK_NOTIFY_WAIT_BLOCK + #define traceTASK_NOTIFY_WAIT_BLOCK() +#endif + +#ifndef traceTASK_NOTIFY_WAIT + #define traceTASK_NOTIFY_WAIT() +#endif + +#ifndef traceTASK_NOTIFY + #define traceTASK_NOTIFY() +#endif + +#ifndef traceTASK_NOTIFY_FROM_ISR + #define traceTASK_NOTIFY_FROM_ISR() +#endif + +#ifndef traceTASK_NOTIFY_GIVE_FROM_ISR + #define traceTASK_NOTIFY_GIVE_FROM_ISR() +#endif + +#ifndef traceSTREAM_BUFFER_CREATE_FAILED + #define traceSTREAM_BUFFER_CREATE_FAILED( xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_CREATE_STATIC_FAILED + #define traceSTREAM_BUFFER_CREATE_STATIC_FAILED( xReturn, xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_CREATE + #define traceSTREAM_BUFFER_CREATE( pxStreamBuffer, xIsMessageBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_DELETE + #define traceSTREAM_BUFFER_DELETE( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RESET + #define traceSTREAM_BUFFER_RESET( xStreamBuffer ) +#endif + +#ifndef traceBLOCKING_ON_STREAM_BUFFER_SEND + #define traceBLOCKING_ON_STREAM_BUFFER_SEND( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND + #define traceSTREAM_BUFFER_SEND( xStreamBuffer, xBytesSent ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND_FAILED + #define traceSTREAM_BUFFER_SEND_FAILED( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_SEND_FROM_ISR + #define traceSTREAM_BUFFER_SEND_FROM_ISR( xStreamBuffer, xBytesSent ) +#endif + +#ifndef traceBLOCKING_ON_STREAM_BUFFER_RECEIVE + #define traceBLOCKING_ON_STREAM_BUFFER_RECEIVE( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE + #define traceSTREAM_BUFFER_RECEIVE( xStreamBuffer, xReceivedLength ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE_FAILED + #define traceSTREAM_BUFFER_RECEIVE_FAILED( xStreamBuffer ) +#endif + +#ifndef traceSTREAM_BUFFER_RECEIVE_FROM_ISR + #define traceSTREAM_BUFFER_RECEIVE_FROM_ISR( xStreamBuffer, xReceivedLength ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#elif configUSE_MALLOC_FAILED_HOOK != 1 + /* Arduino framework integration */ + extern void (*vApplicationMallocFailedHook) ( void ); // see error_hooks.h +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( UBaseType_t ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef portSUPPRESS_TICKS_AND_SLEEP + #define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) +#endif + +#ifndef configEXPECTED_IDLE_TIME_BEFORE_SLEEP + #define configEXPECTED_IDLE_TIME_BEFORE_SLEEP 2 +#endif + +#if configEXPECTED_IDLE_TIME_BEFORE_SLEEP < 2 + #error configEXPECTED_IDLE_TIME_BEFORE_SLEEP must not be less than 2 +#endif + +#ifndef configUSE_TICKLESS_IDLE + #define configUSE_TICKLESS_IDLE 0 +#endif + +#ifndef configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING + #define configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING( x ) +#endif + +#ifndef configPRE_SLEEP_PROCESSING + #define configPRE_SLEEP_PROCESSING( x ) +#endif + +#ifndef configPOST_SLEEP_PROCESSING + #define configPOST_SLEEP_PROCESSING( x ) +#endif + +#ifndef configUSE_QUEUE_SETS + #define configUSE_QUEUE_SETS 0 +#endif + +#ifndef portTASK_USES_FLOATING_POINT + #define portTASK_USES_FLOATING_POINT() +#endif + +#ifndef portALLOCATE_SECURE_CONTEXT + #define portALLOCATE_SECURE_CONTEXT( ulSecureStackSize ) +#endif + +#ifndef portDONT_DISCARD + #define portDONT_DISCARD +#endif + +#ifndef configUSE_TIME_SLICING + #define configUSE_TIME_SLICING 1 +#endif + +#ifndef configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS + #define configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS 0 +#endif + +#ifndef configUSE_STATS_FORMATTING_FUNCTIONS + #define configUSE_STATS_FORMATTING_FUNCTIONS 0 +#endif + +#ifndef portASSERT_IF_INTERRUPT_PRIORITY_INVALID + #define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() +#endif + +#ifndef configUSE_TRACE_FACILITY + #define configUSE_TRACE_FACILITY 0 +#endif + +#ifndef mtCOVERAGE_TEST_MARKER + #define mtCOVERAGE_TEST_MARKER() +#endif + +#ifndef mtCOVERAGE_TEST_DELAY + #define mtCOVERAGE_TEST_DELAY() +#endif + +#ifndef portASSERT_IF_IN_ISR + #define portASSERT_IF_IN_ISR() +#endif + +#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION + #define configUSE_PORT_OPTIMISED_TASK_SELECTION 0 +#endif + +#ifndef configAPPLICATION_ALLOCATED_HEAP + #define configAPPLICATION_ALLOCATED_HEAP 0 +#endif + +#ifndef configUSE_TASK_NOTIFICATIONS + #define configUSE_TASK_NOTIFICATIONS 1 +#endif + +#ifndef configUSE_POSIX_ERRNO + #define configUSE_POSIX_ERRNO 0 +#endif + +#ifndef portTICK_TYPE_IS_ATOMIC + #define portTICK_TYPE_IS_ATOMIC 0 +#endif + +#ifndef configSUPPORT_STATIC_ALLOCATION + /* Defaults to 0 for backward compatibility. */ + #define configSUPPORT_STATIC_ALLOCATION 0 +#endif + +#ifndef configSUPPORT_DYNAMIC_ALLOCATION + /* Defaults to 1 for backward compatibility. */ + #define configSUPPORT_DYNAMIC_ALLOCATION 1 +#endif + +#ifndef configSTACK_DEPTH_TYPE + /* Defaults to uint16_t for backward compatibility, but can be overridden + in FreeRTOSConfig.h if uint16_t is too restrictive. */ + #define configSTACK_DEPTH_TYPE uint16_t +#endif + +#ifndef configMESSAGE_BUFFER_LENGTH_TYPE + /* Defaults to size_t for backward compatibility, but can be overridden + in FreeRTOSConfig.h if lengths will always be less than the number of bytes + in a size_t. */ + #define configMESSAGE_BUFFER_LENGTH_TYPE size_t +#endif + +/* Sanity check the configuration. */ +#if( configUSE_TICKLESS_IDLE != 0 ) + #if( INCLUDE_vTaskSuspend != 1 ) + #error INCLUDE_vTaskSuspend must be set to 1 if configUSE_TICKLESS_IDLE is not set to 0 + #endif /* INCLUDE_vTaskSuspend */ +#endif /* configUSE_TICKLESS_IDLE */ + +#if( ( configSUPPORT_STATIC_ALLOCATION == 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) ) + #error configSUPPORT_STATIC_ALLOCATION and configSUPPORT_DYNAMIC_ALLOCATION cannot both be 0, but can both be 1. +#endif + +#if( ( configUSE_RECURSIVE_MUTEXES == 1 ) && ( configUSE_MUTEXES != 1 ) ) + #error configUSE_MUTEXES must be set to 1 to use recursive mutexes +#endif + +#ifndef configINITIAL_TICK_COUNT + #define configINITIAL_TICK_COUNT 0 +#endif + +#if( portTICK_TYPE_IS_ATOMIC == 0 ) + /* Either variables of tick type cannot be read atomically, or + portTICK_TYPE_IS_ATOMIC was not set - map the critical sections used when + the tick count is returned to the standard critical section macros. */ + #define portTICK_TYPE_ENTER_CRITICAL() portENTER_CRITICAL() + #define portTICK_TYPE_EXIT_CRITICAL() portEXIT_CRITICAL() + #define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR() + #define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( ( x ) ) +#else + /* The tick type can be read atomically, so critical sections used when the + tick count is returned can be defined away. */ + #define portTICK_TYPE_ENTER_CRITICAL() + #define portTICK_TYPE_EXIT_CRITICAL() + #define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() 0 + #define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) ( void ) x +#endif + +/* Definitions to allow backward compatibility with FreeRTOS versions prior to +V8 if desired. */ +#ifndef configENABLE_BACKWARD_COMPATIBILITY + #define configENABLE_BACKWARD_COMPATIBILITY 1 +#endif + +#ifndef configPRINTF + /* configPRINTF() was not defined, so define it away to nothing. To use + configPRINTF() then define it as follows (where MyPrintFunction() is + provided by the application writer): + + void MyPrintFunction(const char *pcFormat, ... ); + #define configPRINTF( X ) MyPrintFunction X + + Then call like a standard printf() function, but placing brackets around + all parameters so they are passed as a single parameter. For example: + configPRINTF( ("Value = %d", MyVariable) ); */ + #define configPRINTF( X ) +#endif + +#ifndef configMAX + /* The application writer has not provided their own MAX macro, so define + the following generic implementation. */ + #define configMAX( a, b ) ( ( ( a ) > ( b ) ) ? ( a ) : ( b ) ) +#endif + +#ifndef configMIN + /* The application writer has not provided their own MAX macro, so define + the following generic implementation. */ + #define configMIN( a, b ) ( ( ( a ) < ( b ) ) ? ( a ) : ( b ) ) +#endif + +#if configENABLE_BACKWARD_COMPATIBILITY == 1 + #define eTaskStateGet eTaskGetState + #define portTickType TickType_t + #define xTaskHandle TaskHandle_t + #define xQueueHandle QueueHandle_t + #define xSemaphoreHandle SemaphoreHandle_t + #define xQueueSetHandle QueueSetHandle_t + #define xQueueSetMemberHandle QueueSetMemberHandle_t + #define xTimeOutType TimeOut_t + #define xMemoryRegion MemoryRegion_t + #define xTaskParameters TaskParameters_t + #define xTaskStatusType TaskStatus_t + #define xTimerHandle TimerHandle_t + #define xCoRoutineHandle CoRoutineHandle_t + #define pdTASK_HOOK_CODE TaskHookFunction_t + #define portTICK_RATE_MS portTICK_PERIOD_MS + #define pcTaskGetTaskName pcTaskGetName + #define pcTimerGetTimerName pcTimerGetName + #define pcQueueGetQueueName pcQueueGetName + #define vTaskGetTaskInfo vTaskGetInfo + + /* Backward compatibility within the scheduler code only - these definitions + are not really required but are included for completeness. */ + #define tmrTIMER_CALLBACK TimerCallbackFunction_t + #define pdTASK_CODE TaskFunction_t + #define xListItem ListItem_t + #define xList List_t + + /* For libraries that break the list data hiding, and access list structure + members directly (which is not supposed to be done). */ + #define pxContainer pvContainer +#endif /* configENABLE_BACKWARD_COMPATIBILITY */ + +#if( configUSE_ALTERNATIVE_API != 0 ) + #error The alternative API was deprecated some time ago, and was removed in FreeRTOS V9.0 0 +#endif + +/* Set configUSE_TASK_FPU_SUPPORT to 0 to omit floating point support even +if floating point hardware is otherwise supported by the FreeRTOS port in use. +This constant is not supported by all FreeRTOS ports that include floating +point support. */ +#ifndef configUSE_TASK_FPU_SUPPORT + #define configUSE_TASK_FPU_SUPPORT 1 +#endif + +/* Set configENABLE_MPU to 1 to enable MPU support and 0 to disable it. This is +currently used in ARMv8M ports. */ +#ifndef configENABLE_MPU + #define configENABLE_MPU 0 +#endif + +/* Set configENABLE_FPU to 1 to enable FPU support and 0 to disable it. This is +currently used in ARMv8M ports. */ +#ifndef configENABLE_FPU + #define configENABLE_FPU 1 +#endif + +/* Set configENABLE_TRUSTZONE to 1 enable TrustZone support and 0 to disable it. +This is currently used in ARMv8M ports. */ +#ifndef configENABLE_TRUSTZONE + #define configENABLE_TRUSTZONE 1 +#endif + +/* Set configRUN_FREERTOS_SECURE_ONLY to 1 to run the FreeRTOS ARMv8M port on +the Secure Side only. */ +#ifndef configRUN_FREERTOS_SECURE_ONLY + #define configRUN_FREERTOS_SECURE_ONLY 0 +#endif + +/* Sometimes the FreeRTOSConfig.h settings only allow a task to be created using + * dynamically allocated RAM, in which case when any task is deleted it is known + * that both the task's stack and TCB need to be freed. Sometimes the + * FreeRTOSConfig.h settings only allow a task to be created using statically + * allocated RAM, in which case when any task is deleted it is known that neither + * the task's stack or TCB should be freed. Sometimes the FreeRTOSConfig.h + * settings allow a task to be created using either statically or dynamically + * allocated RAM, in which case a member of the TCB is used to record whether the + * stack and/or TCB were allocated statically or dynamically, so when a task is + * deleted the RAM that was allocated dynamically is freed again and no attempt is + * made to free the RAM that was allocated statically. + * tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE is only true if it is possible for a + * task to be created using either statically or dynamically allocated RAM. Note + * that if portUSING_MPU_WRAPPERS is 1 then a protected task can be created with + * a statically allocated stack and a dynamically allocated TCB. + * + * The following table lists various combinations of portUSING_MPU_WRAPPERS, + * configSUPPORT_DYNAMIC_ALLOCATION and configSUPPORT_STATIC_ALLOCATION and + * when it is possible to have both static and dynamic allocation: + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + * | MPU | Dynamic | Static | Available Functions | Possible Allocations | Both Dynamic and | Need Free | + * | | | | | | Static Possible | | + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + * | 0 | 0 | 1 | xTaskCreateStatic | TCB - Static, Stack - Static | No | No | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 0 | 1 | 0 | xTaskCreate | TCB - Dynamic, Stack - Dynamic | No | Yes | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 0 | 1 | 1 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateStatic | 2. TCB - Static, Stack - Static | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 0 | 1 | xTaskCreateStatic, | TCB - Static, Stack - Static | No | No | + * | | | | xTaskCreateRestrictedStatic | | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 1 | 0 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateRestricted | 2. TCB - Dynamic, Stack - Static | | | + * +-----|---------|--------|-----------------------------|-----------------------------------|------------------|-----------| + * | 1 | 1 | 1 | xTaskCreate, | 1. TCB - Dynamic, Stack - Dynamic | Yes | Yes | + * | | | | xTaskCreateStatic, | 2. TCB - Dynamic, Stack - Static | | | + * | | | | xTaskCreateRestricted, | 3. TCB - Static, Stack - Static | | | + * | | | | xTaskCreateRestrictedStatic | | | | + * +-----+---------+--------+-----------------------------+-----------------------------------+------------------+-----------+ + */ +#define tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE ( ( ( portUSING_MPU_WRAPPERS == 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) || \ + ( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) ) + +/* + * In line with software engineering best practice, FreeRTOS implements a strict + * data hiding policy, so the real structures used by FreeRTOS to maintain the + * state of tasks, queues, semaphores, etc. are not accessible to the application + * code. However, if the application writer wants to statically allocate such + * an object then the size of the object needs to be know. Dummy structures + * that are guaranteed to have the same size and alignment requirements of the + * real objects are used for this purpose. The dummy list and list item + * structures below are used for inclusion in such a dummy structure. + */ +struct xSTATIC_LIST_ITEM +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + TickType_t xDummy2; + void *pvDummy3[ 4 ]; + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy4; + #endif +}; +typedef struct xSTATIC_LIST_ITEM StaticListItem_t; + +/* See the comments above the struct xSTATIC_LIST_ITEM definition. */ +struct xSTATIC_MINI_LIST_ITEM +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + TickType_t xDummy2; + void *pvDummy3[ 2 ]; +}; +typedef struct xSTATIC_MINI_LIST_ITEM StaticMiniListItem_t; + +/* See the comments above the struct xSTATIC_LIST_ITEM definition. */ +typedef struct xSTATIC_LIST +{ + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy1; + #endif + UBaseType_t uxDummy2; + void *pvDummy3; + StaticMiniListItem_t xDummy4; + #if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 1 ) + TickType_t xDummy5; + #endif +} StaticList_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the Task structure used internally by + * FreeRTOS is not accessible to application code. However, if the application + * writer wants to statically allocate the memory required to create a task then + * the size of the task object needs to be know. The StaticTask_t structure + * below is provided for this purpose. Its sizes and alignment requirements are + * guaranteed to match those of the genuine structure, no matter which + * architecture is being used, and no matter how the values in FreeRTOSConfig.h + * are set. Its contents are somewhat obfuscated in the hope users will + * recognise that it would be unwise to make direct use of the structure members. + */ +typedef struct xSTATIC_TCB +{ + void *pxDummy1; + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xDummy2; + #endif + StaticListItem_t xDummy3[ 2 ]; + UBaseType_t uxDummy5; + void *pxDummy6; + uint8_t ucDummy7[ configMAX_TASK_NAME_LEN ]; + #if ( ( portSTACK_GROWTH > 0 ) || ( configRECORD_STACK_HIGH_ADDRESS == 1 ) ) + void *pxDummy8; + #endif + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + UBaseType_t uxDummy9; + #endif + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy10[ 2 ]; + #endif + #if ( configUSE_MUTEXES == 1 ) + UBaseType_t uxDummy12[ 2 ]; + #endif + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + void *pxDummy14; + #endif + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + void *pvDummy15[ configNUM_THREAD_LOCAL_STORAGE_POINTERS ]; + #endif + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + uint32_t ulDummy16; + #endif + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + struct _reent xDummy17; + #endif + #if ( configUSE_TASK_NOTIFICATIONS == 1 ) + uint32_t ulDummy18; + uint8_t ucDummy19; + #endif + #if ( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + uint8_t uxDummy20; + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + uint8_t ucDummy21; + #endif + #if ( configUSE_POSIX_ERRNO == 1 ) + int iDummy22; + #endif +} StaticTask_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the Queue structure used internally by + * FreeRTOS is not accessible to application code. However, if the application + * writer wants to statically allocate the memory required to create a queue + * then the size of the queue object needs to be know. The StaticQueue_t + * structure below is provided for this purpose. Its sizes and alignment + * requirements are guaranteed to match those of the genuine structure, no + * matter which architecture is being used, and no matter how the values in + * FreeRTOSConfig.h are set. Its contents are somewhat obfuscated in the hope + * users will recognise that it would be unwise to make direct use of the + * structure members. + */ +typedef struct xSTATIC_QUEUE +{ + void *pvDummy1[ 3 ]; + + union + { + void *pvDummy2; + UBaseType_t uxDummy2; + } u; + + StaticList_t xDummy3[ 2 ]; + UBaseType_t uxDummy4[ 3 ]; + uint8_t ucDummy5[ 2 ]; + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucDummy6; + #endif + + #if ( configUSE_QUEUE_SETS == 1 ) + void *pvDummy7; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy8; + uint8_t ucDummy9; + #endif + +} StaticQueue_t; +typedef StaticQueue_t StaticSemaphore_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the event group structure used + * internally by FreeRTOS is not accessible to application code. However, if + * the application writer wants to statically allocate the memory required to + * create an event group then the size of the event group object needs to be + * know. The StaticEventGroup_t structure below is provided for this purpose. + * Its sizes and alignment requirements are guaranteed to match those of the + * genuine structure, no matter which architecture is being used, and no matter + * how the values in FreeRTOSConfig.h are set. Its contents are somewhat + * obfuscated in the hope users will recognise that it would be unwise to make + * direct use of the structure members. + */ +typedef struct xSTATIC_EVENT_GROUP +{ + TickType_t xDummy1; + StaticList_t xDummy2; + + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy3; + #endif + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucDummy4; + #endif + +} StaticEventGroup_t; + +/* + * In line with software engineering best practice, especially when supplying a + * library that is likely to change in future versions, FreeRTOS implements a + * strict data hiding policy. This means the software timer structure used + * internally by FreeRTOS is not accessible to application code. However, if + * the application writer wants to statically allocate the memory required to + * create a software timer then the size of the queue object needs to be know. + * The StaticTimer_t structure below is provided for this purpose. Its sizes + * and alignment requirements are guaranteed to match those of the genuine + * structure, no matter which architecture is being used, and no matter how the + * values in FreeRTOSConfig.h are set. Its contents are somewhat obfuscated in + * the hope users will recognise that it would be unwise to make direct use of + * the structure members. + */ +typedef struct xSTATIC_TIMER +{ + void *pvDummy1; + StaticListItem_t xDummy2; + TickType_t xDummy3; + void *pvDummy5; + TaskFunction_t pvDummy6; + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy7; + #endif + uint8_t ucDummy8; + +} StaticTimer_t; + +/* +* In line with software engineering best practice, especially when supplying a +* library that is likely to change in future versions, FreeRTOS implements a +* strict data hiding policy. This means the stream buffer structure used +* internally by FreeRTOS is not accessible to application code. However, if +* the application writer wants to statically allocate the memory required to +* create a stream buffer then the size of the stream buffer object needs to be +* know. The StaticStreamBuffer_t structure below is provided for this purpose. +* Its size and alignment requirements are guaranteed to match those of the +* genuine structure, no matter which architecture is being used, and no matter +* how the values in FreeRTOSConfig.h are set. Its contents are somewhat +* obfuscated in the hope users will recognise that it would be unwise to make +* direct use of the structure members. +*/ +typedef struct xSTATIC_STREAM_BUFFER +{ + size_t uxDummy1[ 4 ]; + void * pvDummy2[ 3 ]; + uint8_t ucDummy3; + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxDummy4; + #endif +} StaticStreamBuffer_t; + +/* Message buffers are built on stream buffers. */ +typedef StaticStreamBuffer_t StaticMessageBuffer_t; + +#ifdef __cplusplus +} +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/FreeRTOSConfig.h b/lib/FreeRTOS-SAMD51/src/FreeRTOSConfig.h new file mode 100644 index 0000000..8e3f258 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/FreeRTOSConfig.h @@ -0,0 +1,177 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html + *----------------------------------------------------------*/ + +/* Ensure stdint is only used by the compiler, and not the assembler. */ +#ifdef __ICCARM__ + #include +#endif + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configCPU_CLOCK_HZ ( ( unsigned long ) F_CPU ) +#define configTICK_RATE_HZ ( ( TickType_t ) 1000 ) +#define configMAX_PRIORITIES ( 9 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 150 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 20 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) //includes string null terminator +#define configUSE_TRACE_FACILITY 1 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 1 +#define configUSE_MUTEXES 1 +#define configQUEUE_REGISTRY_SIZE 8 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_MALLOC_FAILED_HOOK 1 +#define configUSE_APPLICATION_TASK_TAG 0 +#define configUSE_COUNTING_SEMAPHORES 1 +#define configUSE_QUEUE_SETS 1 +#define configSUPPORT_STATIC_ALLOCATION 0 +#define configSUPPORT_DYNAMIC_ALLOCATION 1 + +/* Run time stats related definitions. */ +#define configGENERATE_RUN_TIME_STATS 1 + +/* Arduino framework integration */ +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vMainConfigureTimerForRunTimeStats() // see runTimeStats_hooks.h +#define portGET_RUN_TIME_COUNTER_VALUE() ulMainGetRunTimeCounterValue() // see runTimeStats_hooks.h + +/* This demo makes use of one or more example stats formatting functions. These +format the raw data provided by the uxTaskGetSystemState() function in to human +readable ASCII form. See the notes in the implementation of vTaskList() within +FreeRTOS/Source/tasks.c for limitations. */ +#define configUSE_STATS_FORMATTING_FUNCTIONS 1 + +#define configUSE_MUTEXES 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 +#define INCLUDE_xTaskGetIdleTaskHandle 1 +#define configUSE_MALLOC_FAILED_HOOK 1 + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Software timer definitions. */ +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY ( 2 ) +#define configTIMER_QUEUE_LENGTH 10 +#define configTIMER_TASK_STACK_DEPTH ( configMINIMAL_STACK_SIZE ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 1 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_eTaskGetState 1 + +/* Arduino framework integration */ +// calibration factor for vNopDelayMS in error_hooks.c +// used to set accuracy of nopDelayMS function +// this was experimentally chosen from a samd51 processor +#define configCAL_FACTOR (F_CPU/6000) + +/* Arduino framework integration */ +#if 0 + // disable interrupts and blink error code + extern void rtosFatalError(void); // see error_hooks.h + #define configASSERT( x ) \ + if( ( x ) == 0 ) { rtosFatalError(); } +#else + // print a error file and line number out user specified serial port + // disable interrupts and blink error code + extern void rtosFatalErrorSerial(unsigned long ulLine, const char * const pcFileName); // see error_hooks.h + extern const char* removePath(const char* path); // see error_hooks.h + #define configASSERT( x ) \ + if( ( x ) == 0 ) { rtosFatalErrorSerial( __LINE__, removePath(__FILE__) ); } + + // assert you can use to also print the value that caused the failure + // Useful for debugging, but not FreeRtos standard + #define configPrintASSERT( x, v1, s, v2 ) \ + if( ( x ) == 0 ) { rtosFatalErrorSerialPrint( __LINE__, removePath(__FILE__), v1, s, v2 ); } +#endif + +/* Arduino framework integration */ +// article to help wade through and figure out proper interrupt settings: +// https://community.arm.com/developer/ip-products/system/b/embedded-blog/posts/cutting-through-the-confusion-with-arm-cortex-m-interrupt-priorities + +/* Cortex-M specific definitions. */ +#define configPRIO_BITS 3 // SAMD51 has only 8 priority levels. pg64 of datasheet. + +/* The lowest interrupt priority that can be used in a call to a "set priority" +function. */ +#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 0x07 // lowest priority + +/* The highest interrupt priority that can be used by any interrupt service +routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL +INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER +PRIORITY THAN THIS! (higher priorities are lower numeric values. */ +// See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. +#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 0x05 // highest priority + +/* Interrupt priorities used by the kernel port layer itself. These are generic +to all Cortex-M ports, and do not rely on any particular library functions. */ +#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) +/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!! +See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) + +/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS +standard names. */ +#define vPortSVCHandler SVC_Handler +#define xPortPendSVHandler PendSV_Handler +//#define xPortSysTickHandler SysTick_Handler + +/* The size of the global output buffer that is available for use when there +are multiple command interpreters running at once (for example, one on a UART +and one on TCP/IP). This is done to prevent an output buffer being defined by +each implementation - which would waste RAM. In this case, there is only one +command interpreter running. */ +#define configCOMMAND_INT_MAX_OUTPUT_SIZE 2048 + +#endif /* FREERTOS_CONFIG_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/FreeRTOS_SAMD51.h b/lib/FreeRTOS-SAMD51/src/FreeRTOS_SAMD51.h new file mode 100644 index 0000000..db9e9d3 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/FreeRTOS_SAMD51.h @@ -0,0 +1,34 @@ + + +#ifndef FREE_RTOS_SAMD21_H +#define FREE_RTOS_SAMD21_H + + #include //required to prevent a compiling error when a cpp header file tries to include this library + + // Rtos core library + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + #include + + // hardware specific port files + #include + #include + + // added helper filed for Arduino support + #include + #include + + +#endif diff --git a/lib/FreeRTOS-SAMD51/src/croutine.c b/lib/FreeRTOS-SAMD51/src/croutine.c new file mode 100644 index 0000000..56c8ac2 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/croutine.c @@ -0,0 +1,353 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +/* Remove the whole file is co-routines are not being used. */ +#if( configUSE_CO_ROUTINES != 0 ) + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + + +/* Lists for ready and blocked co-routines. --------------------*/ +static List_t pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ +static List_t xDelayedCoRoutineList1; /*< Delayed co-routines. */ +static List_t xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ +static List_t * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ +static List_t * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ +static List_t xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ + +/* Other file private variables. --------------------------------*/ +CRCB_t * pxCurrentCoRoutine = NULL; +static UBaseType_t uxTopCoRoutineReadyPriority = 0; +static TickType_t xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; + +/* The initial state of the co-routine when it is created. */ +#define corINITIAL_STATE ( 0 ) + +/* + * Place the co-routine represented by pxCRCB into the appropriate ready queue + * for the priority. It is inserted at the end of the list. + * + * This macro accesses the co-routine ready lists and therefore must not be + * used from within an ISR. + */ +#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ +{ \ + if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ + { \ + uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ + } \ + vListInsertEnd( ( List_t * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ +} + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first co-routine. + */ +static void prvInitialiseCoRoutineLists( void ); + +/* + * Co-routines that are readied by an interrupt cannot be placed directly into + * the ready lists (there is no mutual exclusion). Instead they are placed in + * in the pending ready list in order that they can later be moved to the ready + * list by the co-routine scheduler. + */ +static void prvCheckPendingReadyList( void ); + +/* + * Macro that looks at the list of co-routines that are currently delayed to + * see if any require waking. + * + * Co-routines are stored in the queue in the order of their wake time - + * meaning once one co-routine has been found whose timer has not expired + * we need not look any further down the list. + */ +static void prvCheckDelayedList( void ); + +/*-----------------------------------------------------------*/ + +BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex ) +{ +BaseType_t xReturn; +CRCB_t *pxCoRoutine; + + /* Allocate the memory that will store the co-routine control block. */ + pxCoRoutine = ( CRCB_t * ) pvPortMalloc( sizeof( CRCB_t ) ); + if( pxCoRoutine ) + { + /* If pxCurrentCoRoutine is NULL then this is the first co-routine to + be created and the co-routine data structures need initialising. */ + if( pxCurrentCoRoutine == NULL ) + { + pxCurrentCoRoutine = pxCoRoutine; + prvInitialiseCoRoutineLists(); + } + + /* Check the priority is within limits. */ + if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) + { + uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; + } + + /* Fill out the co-routine control block from the function parameters. */ + pxCoRoutine->uxState = corINITIAL_STATE; + pxCoRoutine->uxPriority = uxPriority; + pxCoRoutine->uxIndex = uxIndex; + pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; + + /* Initialise all the other co-routine control block parameters. */ + vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); + vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); + + /* Set the co-routine control block as a link back from the ListItem_t. + This is so we can get back to the containing CRCB from a generic item + in a list. */ + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), ( ( TickType_t ) configMAX_CO_ROUTINE_PRIORITIES - ( TickType_t ) uxPriority ) ); + + /* Now the co-routine has been initialised it can be added to the ready + list at the correct priority. */ + prvAddCoRoutineToReadyQueue( pxCoRoutine ); + + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList ) +{ +TickType_t xTimeToWake; + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xCoRoutineTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + ( void ) uxListRemove( ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xCoRoutineTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( List_t * ) pxOverflowDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( List_t * ) pxDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + + if( pxEventList ) + { + /* Also add the co-routine to an event list. If this is done then the + function must be called with interrupts disabled. */ + vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckPendingReadyList( void ) +{ + /* Are there any co-routines waiting to get moved to the ready list? These + are co-routines that have been readied by an ISR. The ISR cannot access + the ready lists itself. */ + while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE ) + { + CRCB_t *pxUnblockedCRCB; + + /* The pending ready list can be accessed by an ISR. */ + portDISABLE_INTERRUPTS(); + { + pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); + ( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + } + portENABLE_INTERRUPTS(); + + ( void ) uxListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); + prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckDelayedList( void ) +{ +CRCB_t *pxCRCB; + + xPassedTicks = xTaskGetTickCount() - xLastTickCount; + while( xPassedTicks ) + { + xCoRoutineTickCount++; + xPassedTicks--; + + /* If the tick count has overflowed we need to swap the ready lists. */ + if( xCoRoutineTickCount == 0 ) + { + List_t * pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. If there are + any items in pxDelayedCoRoutineList here then there is an error! */ + pxTemp = pxDelayedCoRoutineList; + pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; + pxOverflowDelayedCoRoutineList = pxTemp; + } + + /* See if this tick has made a timeout expire. */ + while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE ) + { + pxCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ); + + if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) + { + /* Timeout not yet expired. */ + break; + } + + portDISABLE_INTERRUPTS(); + { + /* The event could have occurred just before this critical + section. If this is the case then the generic list item will + have been moved to the pending ready list and the following + line is still valid. Also the pvContainer parameter will have + been set to NULL so the following lines are also valid. */ + ( void ) uxListRemove( &( pxCRCB->xGenericListItem ) ); + + /* Is the co-routine waiting on an event also? */ + if( pxCRCB->xEventListItem.pxContainer ) + { + ( void ) uxListRemove( &( pxCRCB->xEventListItem ) ); + } + } + portENABLE_INTERRUPTS(); + + prvAddCoRoutineToReadyQueue( pxCRCB ); + } + } + + xLastTickCount = xCoRoutineTickCount; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineSchedule( void ) +{ + /* See if any co-routines readied by events need moving to the ready lists. */ + prvCheckPendingReadyList(); + + /* See if any delayed co-routines have timed out. */ + prvCheckDelayedList(); + + /* Find the highest priority queue that contains ready co-routines. */ + while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) + { + if( uxTopCoRoutineReadyPriority == 0 ) + { + /* No more co-routines to check. */ + return; + } + --uxTopCoRoutineReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines + of the same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); + + /* Call the co-routine. */ + ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); + + return; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseCoRoutineLists( void ) +{ +UBaseType_t uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( List_t * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); + } + + vListInitialise( ( List_t * ) &xDelayedCoRoutineList1 ); + vListInitialise( ( List_t * ) &xDelayedCoRoutineList2 ); + vListInitialise( ( List_t * ) &xPendingReadyCoRoutineList ); + + /* Start with pxDelayedCoRoutineList using list1 and the + pxOverflowDelayedCoRoutineList using list2. */ + pxDelayedCoRoutineList = &xDelayedCoRoutineList1; + pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; +} +/*-----------------------------------------------------------*/ + +BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList ) +{ +CRCB_t *pxUnblockedCRCB; +BaseType_t xReturn; + + /* This function is called from within an interrupt. It can only access + event lists and the pending ready list. This function assumes that a + check has already been made to ensure pxEventList is not empty. */ + pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + ( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + vListInsertEnd( ( List_t * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); + + if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} + +#endif /* configUSE_CO_ROUTINES == 0 */ + diff --git a/lib/FreeRTOS-SAMD51/src/croutine.h b/lib/FreeRTOS-SAMD51/src/croutine.h new file mode 100644 index 0000000..8b3b41b --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/croutine.h @@ -0,0 +1,720 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * CoRoutineHandle_t; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( CoRoutineHandle_t, UBaseType_t ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + ListItem_t xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + ListItem_t xEventListItem; /*< List item used to place the CRCB in event lists. */ + UBaseType_t uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + UBaseType_t uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + uint16_t uxState; /*< Used internally by the co-routine implementation. */ +} CRCB_t; /* Co-routine control block. Note must be identical in size down to uxPriority with TCB_t. */ + +/** + * croutine. h + *
+ BaseType_t xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 UBaseType_t uxPriority,
+                                 UBaseType_t uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const TickType_t uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how int32_t to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ uint8_t ucParameterToPass;
+ TaskHandle_t xHandle;
+
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( CoRoutineHandle_t xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( CRCB_t * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( CoRoutineHandle_t xHandle, TickType_t xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_PERIOD_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_PERIOD_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  CoRoutineHandle_t xHandle,
+                  QueueHandle_t pxQueue,
+                  void *pvItemToQueue,
+                  TickType_t xTicksToWait,
+                  BaseType_t *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xNumberToPost = 0;
+ static BaseType_t xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     CoRoutineHandle_t xHandle,
+                     QueueHandle_t pxQueue,
+                     void *pvBuffer,
+                     TickType_t xTicksToWait,
+                     BaseType_t *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xResult;
+ static UBaseType_t uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvItemToQueue,
+                            BaseType_t xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ char cRxedChar;
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvBuffer,
+                            BaseType_t * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/lib/FreeRTOS-SAMD51/src/deprecated_definitions.h b/lib/FreeRTOS-SAMD51/src/deprecated_definitions.h new file mode 100644 index 0000000..9cece98 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/deprecated_definitions.h @@ -0,0 +1,279 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef DEPRECATED_DEFINITIONS_H +#define DEPRECATED_DEFINITIONS_H + + +/* Each FreeRTOS port has a unique portmacro.h header file. Originally a +pre-processor definition was used to ensure the pre-processor found the correct +portmacro.h file for the port being used. That scheme was deprecated in favour +of setting the compiler's include path such that it found the correct +portmacro.h file - removing the need for the constant and allowing the +portmacro.h file to be located anywhere in relation to the port being used. The +definitions below remain in the code for backward compatibility only. New +projects should not use them. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "../../Source/portable/MPLAB/PIC18F/portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "../../Source/portable/MPLAB/PIC32MX/portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#endif /* DEPRECATED_DEFINITIONS_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/error_hooks.cpp b/lib/FreeRTOS-SAMD51/src/error_hooks.cpp new file mode 100644 index 0000000..f3ad39d --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/error_hooks.cpp @@ -0,0 +1,191 @@ + +#include "error_hooks.h" +#include "FreeRTOSConfig.h" //for configCAL_FACTOR +#include + +//************************************************************************ +// global variables + +int ErrorLed_Pin = 13; //default arduino led pin +int ErrorLed_ActiveState = HIGH; + +Stream *errorSerial = NULL; +//************************************************************************ + + +// set the error led to use by the rtos +void vSetErrorLed(uint8_t pin, uint8_t activeState) +{ + ErrorLed_Pin = pin; + ErrorLed_ActiveState = activeState; +} + + +// set the error serial port for debugging asserts and crashes +void vSetErrorSerial(Stream *serial) +{ + errorSerial = serial; +} + + +//************************************************************************ + + +// remove a linux or windows path from the file name +const char* removePath(const char* path) +{ + const char* lastname = path; + for (const char* p=path; *p; ++p) + { + if ( (*p == '/' || *p == '\\') && *(p+1) ) + { + lastname = p+1; + } + + } + return lastname; +} + +//************************************************************************ + +//called on fatal error (interrupts disabled already) +void rtosFatalError(void) +{ + taskDISABLE_INTERRUPTS(); + + while (1) + { + errorBlink(3); + } + +} + +// fatal error print out what file assert failed +void rtosFatalErrorSerial(unsigned long ulLine, const char *pcFileName) +{ + if(errorSerial != NULL) + { + errorSerial->flush(); + errorSerial->println(F("")); + errorSerial->println(F("Fatal Rtos Error")); + + errorSerial->print(F("File: ")); + errorSerial->println(pcFileName); + + errorSerial->print(F("Line: ")); + errorSerial->println(ulLine); + + // allow serial port to flush + errorSerial->flush(); + delay(100); + } + + // proceed the same as other fatal rtos error + rtosFatalError(); +} + +void rtosFatalErrorSerialPrint(unsigned long ulLine, const char *pcFileName, uint8_t valueA, const char* evaluation, uint8_t valueB) +{ + if(errorSerial != NULL) + { + errorSerial->flush(); + errorSerial->println(F("")); + errorSerial->println(F("Fatal Rtos Error")); + + errorSerial->print(F("File: ")); + errorSerial->println(pcFileName); + + errorSerial->print(F("Line: ")); + errorSerial->println(ulLine); + + errorSerial->print(valueA); + errorSerial->print(" "); + errorSerial->print(evaluation); + errorSerial->print(" "); + errorSerial->print(valueB); + errorSerial->println(); + + // allow serial port to flush + errorSerial->flush(); + delay(100); + } + + // proceed the same as other fatal rtos error + rtosFatalError(); +} + +// called on full heap or malloc failure +void vApplicationMallocFailedHook(void) +{ + + if(errorSerial != NULL) + { + errorSerial->println(F("")); + errorSerial->println(F("Malloc Failed")); + + // allow serial port to flush + errorSerial->flush(); + delay(100); + } + + while (1) + { + errorBlink(1); + } +} + +// called on full stack +void vApplicationStackOverflowHook( TaskHandle_t xTask, char *pcTaskName ) +{ + + if(errorSerial != NULL) + { + errorSerial->println(F("")); + errorSerial->print(F("Stack Overflow: ")); + errorSerial->println(pcTaskName); + + // allow serial port to flush + errorSerial->flush(); + delay(100); + } + + while (1) + { + errorBlink(2); + } +} + +//************************************************************************ + + +// blink an error code out the default led when the rtos has crashed +void errorBlink(int errorNumber) +{ + pinMode(ErrorLed_Pin, OUTPUT); + + for(int x=0; x +#include "FreeRTOS.h" +#include "task.h" + +#ifndef ERROR_HOOKS_H +#define ERROR_HOOKS_H + + #ifdef __cplusplus + + //************************************************** + // Cpp function prototypes + //************************************************** + + // set the error serial port for debugging asserts and crashes + void vSetErrorSerial(Stream *serial); + + extern "C" + { + #endif + + //************************************************** + // defines + //************************************************** + + + //************************************************** + // C function prototypes + //************************************************** + + // set the error led to use by the rtos + void vSetErrorLed(uint8_t pin, uint8_t activeState); + + // remove a linux or windows path from a file path + // will leave file name remaining + const char* removePath(const char* path); + + // called on fatal error (interrupts disabled already) + void rtosFatalError(void); + + // fatal error print out what file assert failed + void rtosFatalErrorSerialPrint(unsigned long ulLine, const char *pcFileName, uint8_t valueA, const char* evaluation, uint8_t valueB); + + // called on full heap or malloc failure + void vApplicationMallocFailedHook(void); + + // called on full stack + void vApplicationStackOverflowHook( TaskHandle_t xTask, char *pcTaskName ); + + + + // blink an error code out the default led when the rtos has crashed + void errorBlink(int errorNumber); + + // will delay the processors using nops + // this is used when the rtos has crashed and we cannot use more advanced timing + void vNopDelayMS(unsigned long millis); + + #ifdef __cplusplus + } + #endif + +#endif diff --git a/lib/FreeRTOS-SAMD51/src/event_groups.c b/lib/FreeRTOS-SAMD51/src/event_groups.c new file mode 100644 index 0000000..65a5ff2 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/event_groups.c @@ -0,0 +1,753 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* Standard includes. */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "event_groups.h" + +/* Lint e961, e750 and e9021 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021 See comment above. */ + +/* The following bit fields convey control information in a task's event list +item value. It is important they don't clash with the +taskEVENT_LIST_ITEM_VALUE_IN_USE definition. */ +#if configUSE_16_BIT_TICKS == 1 + #define eventCLEAR_EVENTS_ON_EXIT_BIT 0x0100U + #define eventUNBLOCKED_DUE_TO_BIT_SET 0x0200U + #define eventWAIT_FOR_ALL_BITS 0x0400U + #define eventEVENT_BITS_CONTROL_BYTES 0xff00U +#else + #define eventCLEAR_EVENTS_ON_EXIT_BIT 0x01000000UL + #define eventUNBLOCKED_DUE_TO_BIT_SET 0x02000000UL + #define eventWAIT_FOR_ALL_BITS 0x04000000UL + #define eventEVENT_BITS_CONTROL_BYTES 0xff000000UL +#endif + +typedef struct EventGroupDef_t +{ + EventBits_t uxEventBits; + List_t xTasksWaitingForBits; /*< List of tasks waiting for a bit to be set. */ + + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxEventGroupNumber; + #endif + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the event group is statically allocated to ensure no attempt is made to free the memory. */ + #endif +} EventGroup_t; + +/*-----------------------------------------------------------*/ + +/* + * Test the bits set in uxCurrentEventBits to see if the wait condition is met. + * The wait condition is defined by xWaitForAllBits. If xWaitForAllBits is + * pdTRUE then the wait condition is met if all the bits set in uxBitsToWaitFor + * are also set in uxCurrentEventBits. If xWaitForAllBits is pdFALSE then the + * wait condition is met if any of the bits set in uxBitsToWait for are also set + * in uxCurrentEventBits. + */ +static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + EventGroupHandle_t xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) + { + EventGroup_t *pxEventBits; + + /* A StaticEventGroup_t object must be provided. */ + configASSERT( pxEventGroupBuffer ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticEventGroup_t equals the size of the real + event group structure. */ + volatile size_t xSize = sizeof( StaticEventGroup_t ); + configASSERT( xSize == sizeof( EventGroup_t ) ); + } /*lint !e529 xSize is referenced if configASSERT() is defined. */ + #endif /* configASSERT_DEFINED */ + + /* The user has provided a statically allocated event group - use it. */ + pxEventBits = ( EventGroup_t * ) pxEventGroupBuffer; /*lint !e740 !e9087 EventGroup_t and StaticEventGroup_t are deliberately aliased for data hiding purposes and guaranteed to have the same size and alignment requirement - checked by configASSERT(). */ + + if( pxEventBits != NULL ) + { + pxEventBits->uxEventBits = 0; + vListInitialise( &( pxEventBits->xTasksWaitingForBits ) ); + + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Both static and dynamic allocation can be used, so note that + this event group was created statically in case the event group + is later deleted. */ + pxEventBits->ucStaticallyAllocated = pdTRUE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + + traceEVENT_GROUP_CREATE( pxEventBits ); + } + else + { + /* xEventGroupCreateStatic should only ever be called with + pxEventGroupBuffer pointing to a pre-allocated (compile time + allocated) StaticEventGroup_t variable. */ + traceEVENT_GROUP_CREATE_FAILED(); + } + + return pxEventBits; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + EventGroupHandle_t xEventGroupCreate( void ) + { + EventGroup_t *pxEventBits; + + /* Allocate the event group. Justification for MISRA deviation as + follows: pvPortMalloc() always ensures returned memory blocks are + aligned per the requirements of the MCU stack. In this case + pvPortMalloc() must return a pointer that is guaranteed to meet the + alignment requirements of the EventGroup_t structure - which (if you + follow it through) is the alignment requirements of the TickType_t type + (EventBits_t being of TickType_t itself). Therefore, whenever the + stack alignment requirements are greater than or equal to the + TickType_t alignment requirements the cast is safe. In other cases, + where the natural word size of the architecture is less than + sizeof( TickType_t ), the TickType_t variables will be accessed in two + or more reads operations, and the alignment requirements is only that + of each individual read. */ + pxEventBits = ( EventGroup_t * ) pvPortMalloc( sizeof( EventGroup_t ) ); /*lint !e9087 !e9079 see comment above. */ + + if( pxEventBits != NULL ) + { + pxEventBits->uxEventBits = 0; + vListInitialise( &( pxEventBits->xTasksWaitingForBits ) ); + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* Both static and dynamic allocation can be used, so note this + event group was allocated statically in case the event group is + later deleted. */ + pxEventBits->ucStaticallyAllocated = pdFALSE; + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + traceEVENT_GROUP_CREATE( pxEventBits ); + } + else + { + traceEVENT_GROUP_CREATE_FAILED(); /*lint !e9063 Else branch only exists to allow tracing and does not generate code if trace macros are not defined. */ + } + + return pxEventBits; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) +{ +EventBits_t uxOriginalBitValue, uxReturn; +EventGroup_t *pxEventBits = xEventGroup; +BaseType_t xAlreadyYielded; +BaseType_t xTimeoutOccurred = pdFALSE; + + configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + configASSERT( uxBitsToWaitFor != 0 ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + vTaskSuspendAll(); + { + uxOriginalBitValue = pxEventBits->uxEventBits; + + ( void ) xEventGroupSetBits( xEventGroup, uxBitsToSet ); + + if( ( ( uxOriginalBitValue | uxBitsToSet ) & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + /* All the rendezvous bits are now set - no need to block. */ + uxReturn = ( uxOriginalBitValue | uxBitsToSet ); + + /* Rendezvous always clear the bits. They will have been cleared + already unless this is the only task in the rendezvous. */ + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + + xTicksToWait = 0; + } + else + { + if( xTicksToWait != ( TickType_t ) 0 ) + { + traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor ); + + /* Store the bits that the calling task is waiting for in the + task's event list item so the kernel knows when a match is + found. Then enter the blocked state. */ + vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | eventCLEAR_EVENTS_ON_EXIT_BIT | eventWAIT_FOR_ALL_BITS ), xTicksToWait ); + + /* This assignment is obsolete as uxReturn will get set after + the task unblocks, but some compilers mistakenly generate a + warning about uxReturn being returned without being set if the + assignment is omitted. */ + uxReturn = 0; + } + else + { + /* The rendezvous bits were not set, but no block time was + specified - just return the current event bit value. */ + uxReturn = pxEventBits->uxEventBits; + xTimeoutOccurred = pdTRUE; + } + } + } + xAlreadyYielded = xTaskResumeAll(); + + if( xTicksToWait != ( TickType_t ) 0 ) + { + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The task blocked to wait for its required bits to be set - at this + point either the required bits were set or the block time expired. If + the required bits were set they will have been stored in the task's + event list item, and they should now be retrieved then cleared. */ + uxReturn = uxTaskResetEventItemValue(); + + if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 ) + { + /* The task timed out, just return the current event bit value. */ + taskENTER_CRITICAL(); + { + uxReturn = pxEventBits->uxEventBits; + + /* Although the task got here because it timed out before the + bits it was waiting for were set, it is possible that since it + unblocked another task has set the bits. If this is the case + then it needs to clear the bits before exiting. */ + if( ( uxReturn & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + xTimeoutOccurred = pdTRUE; + } + else + { + /* The task unblocked because the bits were set. */ + } + + /* Control bits might be set as the task had blocked should not be + returned. */ + uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES; + } + + traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred ); + + /* Prevent compiler warnings when trace macros are not used. */ + ( void ) xTimeoutOccurred; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) +{ +EventGroup_t *pxEventBits = xEventGroup; +EventBits_t uxReturn, uxControlBits = 0; +BaseType_t xWaitConditionMet, xAlreadyYielded; +BaseType_t xTimeoutOccurred = pdFALSE; + + /* Check the user is not attempting to wait on the bits used by the kernel + itself, and that at least one bit is being requested. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + configASSERT( uxBitsToWaitFor != 0 ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + vTaskSuspendAll(); + { + const EventBits_t uxCurrentEventBits = pxEventBits->uxEventBits; + + /* Check to see if the wait condition is already met or not. */ + xWaitConditionMet = prvTestWaitCondition( uxCurrentEventBits, uxBitsToWaitFor, xWaitForAllBits ); + + if( xWaitConditionMet != pdFALSE ) + { + /* The wait condition has already been met so there is no need to + block. */ + uxReturn = uxCurrentEventBits; + xTicksToWait = ( TickType_t ) 0; + + /* Clear the wait bits if requested to do so. */ + if( xClearOnExit != pdFALSE ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The wait condition has not been met, but no block time was + specified, so just return the current value. */ + uxReturn = uxCurrentEventBits; + xTimeoutOccurred = pdTRUE; + } + else + { + /* The task is going to block to wait for its required bits to be + set. uxControlBits are used to remember the specified behaviour of + this call to xEventGroupWaitBits() - for use when the event bits + unblock the task. */ + if( xClearOnExit != pdFALSE ) + { + uxControlBits |= eventCLEAR_EVENTS_ON_EXIT_BIT; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xWaitForAllBits != pdFALSE ) + { + uxControlBits |= eventWAIT_FOR_ALL_BITS; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Store the bits that the calling task is waiting for in the + task's event list item so the kernel knows when a match is + found. Then enter the blocked state. */ + vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | uxControlBits ), xTicksToWait ); + + /* This is obsolete as it will get set after the task unblocks, but + some compilers mistakenly generate a warning about the variable + being returned without being set if it is not done. */ + uxReturn = 0; + + traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + if( xTicksToWait != ( TickType_t ) 0 ) + { + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The task blocked to wait for its required bits to be set - at this + point either the required bits were set or the block time expired. If + the required bits were set they will have been stored in the task's + event list item, and they should now be retrieved then cleared. */ + uxReturn = uxTaskResetEventItemValue(); + + if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 ) + { + taskENTER_CRITICAL(); + { + /* The task timed out, just return the current event bit value. */ + uxReturn = pxEventBits->uxEventBits; + + /* It is possible that the event bits were updated between this + task leaving the Blocked state and running again. */ + if( prvTestWaitCondition( uxReturn, uxBitsToWaitFor, xWaitForAllBits ) != pdFALSE ) + { + if( xClearOnExit != pdFALSE ) + { + pxEventBits->uxEventBits &= ~uxBitsToWaitFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + xTimeoutOccurred = pdTRUE; + } + taskEXIT_CRITICAL(); + } + else + { + /* The task unblocked because the bits were set. */ + } + + /* The task blocked so control bits may have been set. */ + uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES; + } + traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred ); + + /* Prevent compiler warnings when trace macros are not used. */ + ( void ) xTimeoutOccurred; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) +{ +EventGroup_t *pxEventBits = xEventGroup; +EventBits_t uxReturn; + + /* Check the user is not attempting to clear the bits used by the kernel + itself. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToClear & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + + taskENTER_CRITICAL(); + { + traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear ); + + /* The value returned is the event group value prior to the bits being + cleared. */ + uxReturn = pxEventBits->uxEventBits; + + /* Clear the bits. */ + pxEventBits->uxEventBits &= ~uxBitsToClear; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) ) + + BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) + { + BaseType_t xReturn; + + traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear ); + xReturn = xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL ); /*lint !e9087 Can't avoid cast to void* as a generic callback function not specific to this use case. Callback casts back to original type so safe. */ + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup ) +{ +UBaseType_t uxSavedInterruptStatus; +EventGroup_t const * const pxEventBits = xEventGroup; +EventBits_t uxReturn; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + uxReturn = pxEventBits->uxEventBits; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return uxReturn; +} /*lint !e818 EventGroupHandle_t is a typedef used in other functions to so can't be pointer to const. */ +/*-----------------------------------------------------------*/ + +EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) +{ +ListItem_t *pxListItem, *pxNext; +ListItem_t const *pxListEnd; +List_t const * pxList; +EventBits_t uxBitsToClear = 0, uxBitsWaitedFor, uxControlBits; +EventGroup_t *pxEventBits = xEventGroup; +BaseType_t xMatchFound = pdFALSE; + + /* Check the user is not attempting to set the bits used by the kernel + itself. */ + configASSERT( xEventGroup ); + configASSERT( ( uxBitsToSet & eventEVENT_BITS_CONTROL_BYTES ) == 0 ); + + pxList = &( pxEventBits->xTasksWaitingForBits ); + pxListEnd = listGET_END_MARKER( pxList ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + vTaskSuspendAll(); + { + traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet ); + + pxListItem = listGET_HEAD_ENTRY( pxList ); + + /* Set the bits. */ + pxEventBits->uxEventBits |= uxBitsToSet; + + /* See if the new bit value should unblock any tasks. */ + while( pxListItem != pxListEnd ) + { + pxNext = listGET_NEXT( pxListItem ); + uxBitsWaitedFor = listGET_LIST_ITEM_VALUE( pxListItem ); + xMatchFound = pdFALSE; + + /* Split the bits waited for from the control bits. */ + uxControlBits = uxBitsWaitedFor & eventEVENT_BITS_CONTROL_BYTES; + uxBitsWaitedFor &= ~eventEVENT_BITS_CONTROL_BYTES; + + if( ( uxControlBits & eventWAIT_FOR_ALL_BITS ) == ( EventBits_t ) 0 ) + { + /* Just looking for single bit being set. */ + if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) != ( EventBits_t ) 0 ) + { + xMatchFound = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) == uxBitsWaitedFor ) + { + /* All bits are set. */ + xMatchFound = pdTRUE; + } + else + { + /* Need all bits to be set, but not all the bits were set. */ + } + + if( xMatchFound != pdFALSE ) + { + /* The bits match. Should the bits be cleared on exit? */ + if( ( uxControlBits & eventCLEAR_EVENTS_ON_EXIT_BIT ) != ( EventBits_t ) 0 ) + { + uxBitsToClear |= uxBitsWaitedFor; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Store the actual event flag value in the task's event list + item before removing the task from the event list. The + eventUNBLOCKED_DUE_TO_BIT_SET bit is set so the task knows + that is was unblocked due to its required bits matching, rather + than because it timed out. */ + vTaskRemoveFromUnorderedEventList( pxListItem, pxEventBits->uxEventBits | eventUNBLOCKED_DUE_TO_BIT_SET ); + } + + /* Move onto the next list item. Note pxListItem->pxNext is not + used here as the list item may have been removed from the event list + and inserted into the ready/pending reading list. */ + pxListItem = pxNext; + } + + /* Clear any bits that matched when the eventCLEAR_EVENTS_ON_EXIT_BIT + bit was set in the control word. */ + pxEventBits->uxEventBits &= ~uxBitsToClear; + } + ( void ) xTaskResumeAll(); + + return pxEventBits->uxEventBits; +} +/*-----------------------------------------------------------*/ + +void vEventGroupDelete( EventGroupHandle_t xEventGroup ) +{ +EventGroup_t *pxEventBits = xEventGroup; +const List_t *pxTasksWaitingForBits = &( pxEventBits->xTasksWaitingForBits ); + + vTaskSuspendAll(); + { + traceEVENT_GROUP_DELETE( xEventGroup ); + + while( listCURRENT_LIST_LENGTH( pxTasksWaitingForBits ) > ( UBaseType_t ) 0 ) + { + /* Unblock the task, returning 0 as the event list is being deleted + and cannot therefore have any bits set. */ + configASSERT( pxTasksWaitingForBits->xListEnd.pxNext != ( const ListItem_t * ) &( pxTasksWaitingForBits->xListEnd ) ); + vTaskRemoveFromUnorderedEventList( pxTasksWaitingForBits->xListEnd.pxNext, eventUNBLOCKED_DUE_TO_BIT_SET ); + } + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) ) + { + /* The event group can only have been allocated dynamically - free + it again. */ + vPortFree( pxEventBits ); + } + #elif( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + { + /* The event group could have been allocated statically or + dynamically, so check before attempting to free the memory. */ + if( pxEventBits->ucStaticallyAllocated == ( uint8_t ) pdFALSE ) + { + vPortFree( pxEventBits ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + } + ( void ) xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ + +/* For internal use only - execute a 'set bits' command that was pended from +an interrupt. */ +void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet ) +{ + ( void ) xEventGroupSetBits( pvEventGroup, ( EventBits_t ) ulBitsToSet ); /*lint !e9079 Can't avoid cast to void* as a generic timer callback prototype. Callback casts back to original type so safe. */ +} +/*-----------------------------------------------------------*/ + +/* For internal use only - execute a 'clear bits' command that was pended from +an interrupt. */ +void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear ) +{ + ( void ) xEventGroupClearBits( pvEventGroup, ( EventBits_t ) ulBitsToClear ); /*lint !e9079 Can't avoid cast to void* as a generic timer callback prototype. Callback casts back to original type so safe. */ +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits ) +{ +BaseType_t xWaitConditionMet = pdFALSE; + + if( xWaitForAllBits == pdFALSE ) + { + /* Task only has to wait for one bit within uxBitsToWaitFor to be + set. Is one already set? */ + if( ( uxCurrentEventBits & uxBitsToWaitFor ) != ( EventBits_t ) 0 ) + { + xWaitConditionMet = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Task has to wait for all the bits in uxBitsToWaitFor to be set. + Are they set already? */ + if( ( uxCurrentEventBits & uxBitsToWaitFor ) == uxBitsToWaitFor ) + { + xWaitConditionMet = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return xWaitConditionMet; +} +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) ) + + BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken ) + { + BaseType_t xReturn; + + traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet ); + xReturn = xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken ); /*lint !e9087 Can't avoid cast to void* as a generic callback function not specific to this use case. Callback casts back to original type so safe. */ + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if (configUSE_TRACE_FACILITY == 1) + + UBaseType_t uxEventGroupGetNumber( void* xEventGroup ) + { + UBaseType_t xReturn; + EventGroup_t const *pxEventBits = ( EventGroup_t * ) xEventGroup; /*lint !e9087 !e9079 EventGroupHandle_t is a pointer to an EventGroup_t, but EventGroupHandle_t is kept opaque outside of this file for data hiding purposes. */ + + if( xEventGroup == NULL ) + { + xReturn = 0; + } + else + { + xReturn = pxEventBits->uxEventGroupNumber; + } + + return xReturn; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vEventGroupSetNumber( void * xEventGroup, UBaseType_t uxEventGroupNumber ) + { + ( ( EventGroup_t * ) xEventGroup )->uxEventGroupNumber = uxEventGroupNumber; /*lint !e9087 !e9079 EventGroupHandle_t is a pointer to an EventGroup_t, but EventGroupHandle_t is kept opaque outside of this file for data hiding purposes. */ + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + + diff --git a/lib/FreeRTOS-SAMD51/src/event_groups.h b/lib/FreeRTOS-SAMD51/src/event_groups.h new file mode 100644 index 0000000..1f38bdb --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/event_groups.h @@ -0,0 +1,757 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef EVENT_GROUPS_H +#define EVENT_GROUPS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include event_groups.h" +#endif + +/* FreeRTOS includes. */ +#include "timers.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * An event group is a collection of bits to which an application can assign a + * meaning. For example, an application may create an event group to convey + * the status of various CAN bus related events in which bit 0 might mean "A CAN + * message has been received and is ready for processing", bit 1 might mean "The + * application has queued a message that is ready for sending onto the CAN + * network", and bit 2 might mean "It is time to send a SYNC message onto the + * CAN network" etc. A task can then test the bit values to see which events + * are active, and optionally enter the Blocked state to wait for a specified + * bit or a group of specified bits to be active. To continue the CAN bus + * example, a CAN controlling task can enter the Blocked state (and therefore + * not consume any processing time) until either bit 0, bit 1 or bit 2 are + * active, at which time the bit that was actually active would inform the task + * which action it had to take (process a received message, send a message, or + * send a SYNC). + * + * The event groups implementation contains intelligence to avoid race + * conditions that would otherwise occur were an application to use a simple + * variable for the same purpose. This is particularly important with respect + * to when a bit within an event group is to be cleared, and when bits have to + * be set and then tested atomically - as is the case where event groups are + * used to create a synchronisation point between multiple tasks (a + * 'rendezvous'). + * + * \defgroup EventGroup + */ + + + +/** + * event_groups.h + * + * Type by which event groups are referenced. For example, a call to + * xEventGroupCreate() returns an EventGroupHandle_t variable that can then + * be used as a parameter to other event group functions. + * + * \defgroup EventGroupHandle_t EventGroupHandle_t + * \ingroup EventGroup + */ +struct EventGroupDef_t; +typedef struct EventGroupDef_t * EventGroupHandle_t; + +/* + * The type that holds event bits always matches TickType_t - therefore the + * number of bits it holds is set by configUSE_16_BIT_TICKS (16 bits if set to 1, + * 32 bits if set to 0. + * + * \defgroup EventBits_t EventBits_t + * \ingroup EventGroup + */ +typedef TickType_t EventBits_t; + +/** + * event_groups.h + *
+ EventGroupHandle_t xEventGroupCreate( void );
+ 
+ * + * Create a new event group. + * + * Internally, within the FreeRTOS implementation, event groups use a [small] + * block of memory, in which the event group's structure is stored. If an event + * groups is created using xEventGropuCreate() then the required memory is + * automatically dynamically allocated inside the xEventGroupCreate() function. + * (see http://www.freertos.org/a00111.html). If an event group is created + * using xEventGropuCreateStatic() then the application writer must instead + * provide the memory that will get used by the event group. + * xEventGroupCreateStatic() therefore allows an event group to be created + * without using any dynamic memory allocation. + * + * Although event groups are not related to ticks, for internal implementation + * reasons the number of bits available for use in an event group is dependent + * on the configUSE_16_BIT_TICKS setting in FreeRTOSConfig.h. If + * configUSE_16_BIT_TICKS is 1 then each event group contains 8 usable bits (bit + * 0 to bit 7). If configUSE_16_BIT_TICKS is set to 0 then each event group has + * 24 usable bits (bit 0 to bit 23). The EventBits_t type is used to store + * event bits within an event group. + * + * @return If the event group was created then a handle to the event group is + * returned. If there was insufficient FreeRTOS heap available to create the + * event group then NULL is returned. See http://www.freertos.org/a00111.html + * + * Example usage: +
+	// Declare a variable to hold the created event group.
+	EventGroupHandle_t xCreatedEventGroup;
+
+	// Attempt to create the event group.
+	xCreatedEventGroup = xEventGroupCreate();
+
+	// Was the event group created successfully?
+	if( xCreatedEventGroup == NULL )
+	{
+		// The event group was not created because there was insufficient
+		// FreeRTOS heap available.
+	}
+	else
+	{
+		// The event group was created.
+	}
+   
+ * \defgroup xEventGroupCreate xEventGroupCreate + * \ingroup EventGroup + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + EventGroupHandle_t xEventGroupCreate( void ) PRIVILEGED_FUNCTION; +#endif + +/** + * event_groups.h + *
+ EventGroupHandle_t xEventGroupCreateStatic( EventGroupHandle_t * pxEventGroupBuffer );
+ 
+ * + * Create a new event group. + * + * Internally, within the FreeRTOS implementation, event groups use a [small] + * block of memory, in which the event group's structure is stored. If an event + * groups is created using xEventGropuCreate() then the required memory is + * automatically dynamically allocated inside the xEventGroupCreate() function. + * (see http://www.freertos.org/a00111.html). If an event group is created + * using xEventGropuCreateStatic() then the application writer must instead + * provide the memory that will get used by the event group. + * xEventGroupCreateStatic() therefore allows an event group to be created + * without using any dynamic memory allocation. + * + * Although event groups are not related to ticks, for internal implementation + * reasons the number of bits available for use in an event group is dependent + * on the configUSE_16_BIT_TICKS setting in FreeRTOSConfig.h. If + * configUSE_16_BIT_TICKS is 1 then each event group contains 8 usable bits (bit + * 0 to bit 7). If configUSE_16_BIT_TICKS is set to 0 then each event group has + * 24 usable bits (bit 0 to bit 23). The EventBits_t type is used to store + * event bits within an event group. + * + * @param pxEventGroupBuffer pxEventGroupBuffer must point to a variable of type + * StaticEventGroup_t, which will be then be used to hold the event group's data + * structures, removing the need for the memory to be allocated dynamically. + * + * @return If the event group was created then a handle to the event group is + * returned. If pxEventGroupBuffer was NULL then NULL is returned. + * + * Example usage: +
+	// StaticEventGroup_t is a publicly accessible structure that has the same
+	// size and alignment requirements as the real event group structure.  It is
+	// provided as a mechanism for applications to know the size of the event
+	// group (which is dependent on the architecture and configuration file
+	// settings) without breaking the strict data hiding policy by exposing the
+	// real event group internals.  This StaticEventGroup_t variable is passed
+	// into the xSemaphoreCreateEventGroupStatic() function and is used to store
+	// the event group's data structures
+	StaticEventGroup_t xEventGroupBuffer;
+
+	// Create the event group without dynamically allocating any memory.
+	xEventGroup = xEventGroupCreateStatic( &xEventGroupBuffer );
+   
+ */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + EventGroupHandle_t xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) PRIVILEGED_FUNCTION; +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupWaitBits( 	EventGroupHandle_t xEventGroup,
+										const EventBits_t uxBitsToWaitFor,
+										const BaseType_t xClearOnExit,
+										const BaseType_t xWaitForAllBits,
+										const TickType_t xTicksToWait );
+ 
+ * + * [Potentially] block to wait for one or more bits to be set within a + * previously created event group. + * + * This function cannot be called from an interrupt. + * + * @param xEventGroup The event group in which the bits are being tested. The + * event group must have previously been created using a call to + * xEventGroupCreate(). + * + * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test + * inside the event group. For example, to wait for bit 0 and/or bit 2 set + * uxBitsToWaitFor to 0x05. To wait for bits 0 and/or bit 1 and/or bit 2 set + * uxBitsToWaitFor to 0x07. Etc. + * + * @param xClearOnExit If xClearOnExit is set to pdTRUE then any bits within + * uxBitsToWaitFor that are set within the event group will be cleared before + * xEventGroupWaitBits() returns if the wait condition was met (if the function + * returns for a reason other than a timeout). If xClearOnExit is set to + * pdFALSE then the bits set in the event group are not altered when the call to + * xEventGroupWaitBits() returns. + * + * @param xWaitForAllBits If xWaitForAllBits is set to pdTRUE then + * xEventGroupWaitBits() will return when either all the bits in uxBitsToWaitFor + * are set or the specified block time expires. If xWaitForAllBits is set to + * pdFALSE then xEventGroupWaitBits() will return when any one of the bits set + * in uxBitsToWaitFor is set or the specified block time expires. The block + * time is specified by the xTicksToWait parameter. + * + * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait + * for one/all (depending on the xWaitForAllBits value) of the bits specified by + * uxBitsToWaitFor to become set. + * + * @return The value of the event group at the time either the bits being waited + * for became set, or the block time expired. Test the return value to know + * which bits were set. If xEventGroupWaitBits() returned because its timeout + * expired then not all the bits being waited for will be set. If + * xEventGroupWaitBits() returned because the bits it was waiting for were set + * then the returned value is the event group value before any bits were + * automatically cleared in the case that xClearOnExit parameter was set to + * pdTRUE. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+   const TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+		// Wait a maximum of 100ms for either bit 0 or bit 4 to be set within
+		// the event group.  Clear the bits before exiting.
+		uxBits = xEventGroupWaitBits(
+					xEventGroup,	// The event group being tested.
+					BIT_0 | BIT_4,	// The bits within the event group to wait for.
+					pdTRUE,			// BIT_0 and BIT_4 should be cleared before returning.
+					pdFALSE,		// Don't wait for both bits, either bit will do.
+					xTicksToWait );	// Wait a maximum of 100ms for either bit to be set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// xEventGroupWaitBits() returned because both bits were set.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_0 was set.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_4 was set.
+		}
+		else
+		{
+			// xEventGroupWaitBits() returned because xTicksToWait ticks passed
+			// without either BIT_0 or BIT_4 becoming set.
+		}
+   }
+   
+ * \defgroup xEventGroupWaitBits xEventGroupWaitBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear );
+ 
+ * + * Clear bits within an event group. This function cannot be called from an + * interrupt. + * + * @param xEventGroup The event group in which the bits are to be cleared. + * + * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear + * in the event group. For example, to clear bit 3 only, set uxBitsToClear to + * 0x08. To clear bit 3 and bit 0 set uxBitsToClear to 0x09. + * + * @return The value of the event group before the specified bits were cleared. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Clear bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupClearBits(
+								xEventGroup,	// The event group being updated.
+								BIT_0 | BIT_4 );// The bits being cleared.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 were set before xEventGroupClearBits() was
+			// called.  Both will now be clear (not set).
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 were set in the first place.
+		}
+   }
+   
+ * \defgroup xEventGroupClearBits xEventGroupClearBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ 
+ * + * A version of xEventGroupClearBits() that can be called from an interrupt. + * + * Setting bits in an event group is not a deterministic operation because there + * are an unknown number of tasks that may be waiting for the bit or bits being + * set. FreeRTOS does not allow nondeterministic operations to be performed + * while interrupts are disabled, so protects event groups that are accessed + * from tasks by suspending the scheduler rather than disabling interrupts. As + * a result event groups cannot be accessed directly from an interrupt service + * routine. Therefore xEventGroupClearBitsFromISR() sends a message to the + * timer task to have the clear operation performed in the context of the timer + * task. + * + * @param xEventGroup The event group in which the bits are to be cleared. + * + * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear. + * For example, to clear bit 3 only, set uxBitsToClear to 0x08. To clear bit 3 + * and bit 0 set uxBitsToClear to 0x09. + * + * @return If the request to execute the function was posted successfully then + * pdPASS is returned, otherwise pdFALSE is returned. pdFALSE will be returned + * if the timer service queue was full. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+		// Clear bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupClearBitsFromISR(
+							xEventGroup,	 // The event group being updated.
+							BIT_0 | BIT_4 ); // The bits being set.
+
+		if( xResult == pdPASS )
+		{
+			// The message was posted successfully.
+		}
+  }
+   
+ * \defgroup xEventGroupClearBitsFromISR xEventGroupClearBitsFromISR + * \ingroup EventGroup + */ +#if( configUSE_TRACE_FACILITY == 1 ) + BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) PRIVILEGED_FUNCTION; +#else + #define xEventGroupClearBitsFromISR( xEventGroup, uxBitsToClear ) xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL ) +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ 
+ * + * Set bits within an event group. + * This function cannot be called from an interrupt. xEventGroupSetBitsFromISR() + * is a version that can be called from an interrupt. + * + * Setting bits in an event group will automatically unblock tasks that are + * blocked waiting for the bits. + * + * @param xEventGroup The event group in which the bits are to be set. + * + * @param uxBitsToSet A bitwise value that indicates the bit or bits to set. + * For example, to set bit 3 only, set uxBitsToSet to 0x08. To set bit 3 + * and bit 0 set uxBitsToSet to 0x09. + * + * @return The value of the event group at the time the call to + * xEventGroupSetBits() returns. There are two reasons why the returned value + * might have the bits specified by the uxBitsToSet parameter cleared. First, + * if setting a bit results in a task that was waiting for the bit leaving the + * blocked state then it is possible the bit will be cleared automatically + * (see the xClearBitOnExit parameter of xEventGroupWaitBits()). Second, any + * unblocked (or otherwise Ready state) task that has a priority above that of + * the task that called xEventGroupSetBits() will execute and may change the + * event group value before the call to xEventGroupSetBits() returns. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupSetBits(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4 );// The bits being set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 remained set when the function returned.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 remained set when the function returned, but bit 4 was
+			// cleared.  It might be that bit 4 was cleared automatically as a
+			// task that was waiting for bit 4 was removed from the Blocked
+			// state.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 remained set when the function returned, but bit 0 was
+			// cleared.  It might be that bit 0 was cleared automatically as a
+			// task that was waiting for bit 0 was removed from the Blocked
+			// state.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 remained set.  It might be that a task
+			// was waiting for both of the bits to be set, and the bits were
+			// cleared as the task left the Blocked state.
+		}
+   }
+   
+ * \defgroup xEventGroupSetBits xEventGroupSetBits + * \ingroup EventGroup + */ +EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken );
+ 
+ * + * A version of xEventGroupSetBits() that can be called from an interrupt. + * + * Setting bits in an event group is not a deterministic operation because there + * are an unknown number of tasks that may be waiting for the bit or bits being + * set. FreeRTOS does not allow nondeterministic operations to be performed in + * interrupts or from critical sections. Therefore xEventGroupSetBitsFromISR() + * sends a message to the timer task to have the set operation performed in the + * context of the timer task - where a scheduler lock is used in place of a + * critical section. + * + * @param xEventGroup The event group in which the bits are to be set. + * + * @param uxBitsToSet A bitwise value that indicates the bit or bits to set. + * For example, to set bit 3 only, set uxBitsToSet to 0x08. To set bit 3 + * and bit 0 set uxBitsToSet to 0x09. + * + * @param pxHigherPriorityTaskWoken As mentioned above, calling this function + * will result in a message being sent to the timer daemon task. If the + * priority of the timer daemon task is higher than the priority of the + * currently running task (the task the interrupt interrupted) then + * *pxHigherPriorityTaskWoken will be set to pdTRUE by + * xEventGroupSetBitsFromISR(), indicating that a context switch should be + * requested before the interrupt exits. For that reason + * *pxHigherPriorityTaskWoken must be initialised to pdFALSE. See the + * example code below. + * + * @return If the request to execute the function was posted successfully then + * pdPASS is returned, otherwise pdFALSE is returned. pdFALSE will be returned + * if the timer service queue was full. + * + * Example usage: +
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+   BaseType_t xHigherPriorityTaskWoken, xResult;
+
+		// xHigherPriorityTaskWoken must be initialised to pdFALSE.
+		xHigherPriorityTaskWoken = pdFALSE;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupSetBitsFromISR(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4   // The bits being set.
+							&xHigherPriorityTaskWoken );
+
+		// Was the message posted successfully?
+		if( xResult == pdPASS )
+		{
+			// If xHigherPriorityTaskWoken is now set to pdTRUE then a context
+			// switch should be requested.  The macro used is port specific and
+			// will be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() -
+			// refer to the documentation page for the port being used.
+			portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+		}
+  }
+   
+ * \defgroup xEventGroupSetBitsFromISR xEventGroupSetBitsFromISR + * \ingroup EventGroup + */ +#if( configUSE_TRACE_FACILITY == 1 ) + BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +#else + #define xEventGroupSetBitsFromISR( xEventGroup, uxBitsToSet, pxHigherPriorityTaskWoken ) xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken ) +#endif + +/** + * event_groups.h + *
+	EventBits_t xEventGroupSync(	EventGroupHandle_t xEventGroup,
+									const EventBits_t uxBitsToSet,
+									const EventBits_t uxBitsToWaitFor,
+									TickType_t xTicksToWait );
+ 
+ * + * Atomically set bits within an event group, then wait for a combination of + * bits to be set within the same event group. This functionality is typically + * used to synchronise multiple tasks, where each task has to wait for the other + * tasks to reach a synchronisation point before proceeding. + * + * This function cannot be used from an interrupt. + * + * The function will return before its block time expires if the bits specified + * by the uxBitsToWait parameter are set, or become set within that time. In + * this case all the bits specified by uxBitsToWait will be automatically + * cleared before the function returns. + * + * @param xEventGroup The event group in which the bits are being tested. The + * event group must have previously been created using a call to + * xEventGroupCreate(). + * + * @param uxBitsToSet The bits to set in the event group before determining + * if, and possibly waiting for, all the bits specified by the uxBitsToWait + * parameter are set. + * + * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test + * inside the event group. For example, to wait for bit 0 and bit 2 set + * uxBitsToWaitFor to 0x05. To wait for bits 0 and bit 1 and bit 2 set + * uxBitsToWaitFor to 0x07. Etc. + * + * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait + * for all of the bits specified by uxBitsToWaitFor to become set. + * + * @return The value of the event group at the time either the bits being waited + * for became set, or the block time expired. Test the return value to know + * which bits were set. If xEventGroupSync() returned because its timeout + * expired then not all the bits being waited for will be set. If + * xEventGroupSync() returned because all the bits it was waiting for were + * set then the returned value is the event group value before any bits were + * automatically cleared. + * + * Example usage: +
+ // Bits used by the three tasks.
+ #define TASK_0_BIT		( 1 << 0 )
+ #define TASK_1_BIT		( 1 << 1 )
+ #define TASK_2_BIT		( 1 << 2 )
+
+ #define ALL_SYNC_BITS ( TASK_0_BIT | TASK_1_BIT | TASK_2_BIT )
+
+ // Use an event group to synchronise three tasks.  It is assumed this event
+ // group has already been created elsewhere.
+ EventGroupHandle_t xEventBits;
+
+ void vTask0( void *pvParameters )
+ {
+ EventBits_t uxReturn;
+ TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 0 in the event flag to note this task has reached the
+		// sync point.  The other two tasks will set the other two bits defined
+		// by ALL_SYNC_BITS.  All three tasks have reached the synchronisation
+		// point when all the ALL_SYNC_BITS are set.  Wait a maximum of 100ms
+		// for this to happen.
+		uxReturn = xEventGroupSync( xEventBits, TASK_0_BIT, ALL_SYNC_BITS, xTicksToWait );
+
+		if( ( uxReturn & ALL_SYNC_BITS ) == ALL_SYNC_BITS )
+		{
+			// All three tasks reached the synchronisation point before the call
+			// to xEventGroupSync() timed out.
+		}
+	}
+ }
+
+ void vTask1( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 1 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_1_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	 }
+ }
+
+ void vTask2( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 2 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_2_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	}
+ }
+
+ 
+ * \defgroup xEventGroupSync xEventGroupSync + * \ingroup EventGroup + */ +EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + + +/** + * event_groups.h + *
+	EventBits_t xEventGroupGetBits( EventGroupHandle_t xEventGroup );
+ 
+ * + * Returns the current value of the bits in an event group. This function + * cannot be used from an interrupt. + * + * @param xEventGroup The event group being queried. + * + * @return The event group bits at the time xEventGroupGetBits() was called. + * + * \defgroup xEventGroupGetBits xEventGroupGetBits + * \ingroup EventGroup + */ +#define xEventGroupGetBits( xEventGroup ) xEventGroupClearBits( xEventGroup, 0 ) + +/** + * event_groups.h + *
+	EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup );
+ 
+ * + * A version of xEventGroupGetBits() that can be called from an ISR. + * + * @param xEventGroup The event group being queried. + * + * @return The event group bits at the time xEventGroupGetBitsFromISR() was called. + * + * \defgroup xEventGroupGetBitsFromISR xEventGroupGetBitsFromISR + * \ingroup EventGroup + */ +EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION; + +/** + * event_groups.h + *
+	void xEventGroupDelete( EventGroupHandle_t xEventGroup );
+ 
+ * + * Delete an event group that was previously created by a call to + * xEventGroupCreate(). Tasks that are blocked on the event group will be + * unblocked and obtain 0 as the event group's value. + * + * @param xEventGroup The event group being deleted. + */ +void vEventGroupDelete( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION; + +/* For internal use only. */ +void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet ) PRIVILEGED_FUNCTION; +void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear ) PRIVILEGED_FUNCTION; + + +#if (configUSE_TRACE_FACILITY == 1) + UBaseType_t uxEventGroupGetNumber( void* xEventGroup ) PRIVILEGED_FUNCTION; + void vEventGroupSetNumber( void* xEventGroup, UBaseType_t uxEventGroupNumber ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* EVENT_GROUPS_H */ + + diff --git a/lib/FreeRTOS-SAMD51/src/heap_4bis.c b/lib/FreeRTOS-SAMD51/src/heap_4bis.c new file mode 100644 index 0000000..c6d3354 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/heap_4bis.c @@ -0,0 +1,605 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* + * A sample implementation of pvPortMalloc() and vPortFree() that combines + * (coalescences) adjacent memory blocks as they are freed, and in so doing + * limits memory fragmentation. + * + * See heap_1.c, heap_2.c and heap_3.c for alternative implementations, and the + * memory management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 0 ) + #error This file must not be used if configSUPPORT_DYNAMIC_ALLOCATION is 0 +#endif + +/* Block sizes must not get too small. */ +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( xHeapStructSize << 1 ) ) + +/* Assumes 8bit bytes! */ +#define heapBITS_PER_BYTE ( ( size_t ) 8 ) + +/* Allocate the memory for the heap. */ +#if( configAPPLICATION_ALLOCATED_HEAP == 1 ) + /* The application writer has already defined the array used for the RTOS + heap - probably so it can be placed in a special segment or address. */ + extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#else + static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ]; +#endif /* configAPPLICATION_ALLOCATED_HEAP */ + +/* Define the linked list structure. This is used to link free blocks in order +of their memory address. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} BlockLink_t; + +/*-----------------------------------------------------------*/ + +/* + * Inserts a block of memory that is being freed into the correct position in + * the list of free memory blocks. The block being freed will be merged with + * the block in front it and/or the block behind it if the memory blocks are + * adjacent to each other. + */ +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ); + +/* + * Called automatically to setup the required heap structures the first time + * pvPortMalloc() is called. + */ +static void prvHeapInit( void ); + +/*-----------------------------------------------------------*/ + +/* The size of the structure placed at the beginning of each allocated memory +block must by correctly byte aligned. */ +static const size_t xHeapStructSize = ( sizeof( BlockLink_t ) + ( ( size_t ) ( portBYTE_ALIGNMENT - 1 ) ) ) & ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + +/* Create a couple of list links to mark the start and end of the list. */ +static BlockLink_t xStart, *pxEnd = NULL; + +/* Keeps track of the number of free bytes remaining, but says nothing about +fragmentation. */ +static size_t xFreeBytesRemaining = 0U; +static size_t xMinimumEverFreeBytesRemaining = 0U; + +/* Gets set to the top bit of an size_t type. When this bit in the xBlockSize +member of an BlockLink_t structure is set then the block belongs to the +application. When the bit is free the block is still part of the free heap +space. */ +static size_t xBlockAllocatedBit = 0; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ + BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink; + void *pvReturn = NULL; + + vTaskSuspendAll(); + { + /* If this is the first call to malloc then the heap will require + initialisation to setup the list of free blocks. */ + if( pxEnd == NULL ) + { + prvHeapInit(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Check the requested block size is not so large that the top bit is + set. The top bit of the block size member of the BlockLink_t structure + is used to determine who owns the block - the application or the + kernel, so it must be free. */ + if( ( xWantedSize & xBlockAllocatedBit ) == 0 ) + { + /* The wanted size is increased so it can contain a BlockLink_t + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += xHeapStructSize; + + /* Ensure that blocks are always aligned to the required number + of bytes. */ + if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0x00 ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + configASSERT( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) == 0 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( ( xWantedSize > 0 ) && ( xWantedSize <= xFreeBytesRemaining ) ) + { + /* Traverse the list from the start (lowest address) block until + one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If the end marker was reached then a block of adequate size + was not found. */ + if( pxBlock != pxEnd ) + { + /* Return the memory space pointed to - jumping over the + BlockLink_t structure at its start. */ + pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + xHeapStructSize ); + + /* This block is being returned for use so must be taken out + of the list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into + two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new + block following the number of bytes requested. The void + cast is used to prevent byte alignment warnings from the + compiler. */ + pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize ); + configASSERT( ( ( ( size_t ) pxNewBlockLink ) & portBYTE_ALIGNMENT_MASK ) == 0 ); + + /* Calculate the sizes of two blocks split from the + single block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( pxNewBlockLink ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + + if( xFreeBytesRemaining < xMinimumEverFreeBytesRemaining ) + { + xMinimumEverFreeBytesRemaining = xFreeBytesRemaining; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The block is being returned - it is allocated and owned + by the application and has no "next" block. */ + pxBlock->xBlockSize |= xBlockAllocatedBit; + pxBlock->pxNextFreeBlock = NULL; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceMALLOC( pvReturn, xWantedSize ); + } + ( void ) xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif + + configASSERT( ( ( ( size_t ) pvReturn ) & ( size_t ) portBYTE_ALIGNMENT_MASK ) == 0 ); + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + uint8_t *puc = ( uint8_t * ) pv; + BlockLink_t *pxLink; + + if( pv != NULL ) + { + /* The memory being freed will have an BlockLink_t structure immediately + before it. */ + puc -= xHeapStructSize; + + /* This casting is to keep the compiler from issuing warnings. */ + pxLink = ( void * ) puc; + + /* Check the block is actually allocated. */ + configASSERT( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ); + configASSERT( pxLink->pxNextFreeBlock == NULL ); + + if( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 ) + { + if( pxLink->pxNextFreeBlock == NULL ) + { + /* The block is being returned to the heap - it is no longer + allocated. */ + pxLink->xBlockSize &= ~xBlockAllocatedBit; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + xFreeBytesRemaining += pxLink->xBlockSize; + traceFREE( pv, pxLink->xBlockSize ); + prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) ); + } + ( void ) xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetMinimumEverFreeHeapSize( void ) +{ + return xMinimumEverFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* This just exists to keep the linker quiet. */ +} +/*-----------------------------------------------------------*/ + +static void prvHeapInit( void ) +{ +BlockLink_t *pxFirstFreeBlock; +uint8_t *pucAlignedHeap; +size_t uxAddress; +size_t xTotalHeapSize = configTOTAL_HEAP_SIZE; + + /* Ensure the heap starts on a correctly aligned boundary. */ + uxAddress = ( size_t ) ucHeap; + + if( ( uxAddress & portBYTE_ALIGNMENT_MASK ) != 0 ) + { + uxAddress += ( portBYTE_ALIGNMENT - 1 ); + uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + xTotalHeapSize -= uxAddress - ( size_t ) ucHeap; + } + + pucAlignedHeap = ( uint8_t * ) uxAddress; + + /* xStart is used to hold a pointer to the first item in the list of free + blocks. The void cast is used to prevent compiler warnings. */ + xStart.pxNextFreeBlock = ( void * ) pucAlignedHeap; + xStart.xBlockSize = ( size_t ) 0; + + /* pxEnd is used to mark the end of the list of free blocks and is inserted + at the end of the heap space. */ + uxAddress = ( ( size_t ) pucAlignedHeap ) + xTotalHeapSize; + uxAddress -= xHeapStructSize; + uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK ); + pxEnd = ( void * ) uxAddress; + pxEnd->xBlockSize = 0; + pxEnd->pxNextFreeBlock = NULL; + + /* To start with there is a single free block that is sized to take up the + entire heap space, minus the space taken by pxEnd. */ + pxFirstFreeBlock = ( void * ) pucAlignedHeap; + pxFirstFreeBlock->xBlockSize = uxAddress - ( size_t ) pxFirstFreeBlock; + pxFirstFreeBlock->pxNextFreeBlock = pxEnd; + + /* Only one block exists - and it covers the entire usable heap space. */ + xMinimumEverFreeBytesRemaining = pxFirstFreeBlock->xBlockSize; + xFreeBytesRemaining = pxFirstFreeBlock->xBlockSize; + + /* Work out the position of the top bit in a size_t variable. */ + xBlockAllocatedBit = ( ( size_t ) 1 ) << ( ( sizeof( size_t ) * heapBITS_PER_BYTE ) - 1 ); +} +/*-----------------------------------------------------------*/ + +static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert ) +{ +BlockLink_t *pxIterator; +uint8_t *puc; + + /* Iterate through the list until a block is found that has a higher address + than the block being inserted. */ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock < pxBlockToInsert; pxIterator = pxIterator->pxNextFreeBlock ) + { + /* Nothing to do here, just iterate to the right position. */ + } + + /* Do the block being inserted, and the block it is being inserted after + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxIterator; + if( ( puc + pxIterator->xBlockSize ) == ( uint8_t * ) pxBlockToInsert ) + { + pxIterator->xBlockSize += pxBlockToInsert->xBlockSize; + pxBlockToInsert = pxIterator; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Do the block being inserted, and the block it is being inserted before + make a contiguous block of memory? */ + puc = ( uint8_t * ) pxBlockToInsert; + if( ( puc + pxBlockToInsert->xBlockSize ) == ( uint8_t * ) pxIterator->pxNextFreeBlock ) + { + if( pxIterator->pxNextFreeBlock != pxEnd ) + { + /* Form one big block from the two blocks. */ + pxBlockToInsert->xBlockSize += pxIterator->pxNextFreeBlock->xBlockSize; + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock->pxNextFreeBlock; + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxEnd; + } + } + else + { + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; + } + + /* If the block being inserted plugged a gab, so was merged with the block + before and the block after, then it's pxNextFreeBlock pointer will have + already been set, and should not be set here as that would make it point + to itself. */ + if( pxIterator != pxBlockToInsert ) + { + pxIterator->pxNextFreeBlock = pxBlockToInsert; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} + +// non standard contributed feature that can be enabled +#define ENABLE_CALLOC_REALLOC 0 + +#if ENABLE_CALLOC_REALLOC + +void *pvPortRealloc (void* ptr, size_t _size) +{ + void *retVal = NULL; + if (ptr == NULL && _size > 0) + { + retVal = pvPortMalloc(_size); + } + else if (ptr != NULL && _size == 0) + { + vPortFree(ptr); + retVal = NULL; + } + else if (ptr != NULL && _size > 0) + { + vTaskSuspendAll(); //thread safety + { + if( pxEnd == NULL ) + { + prvHeapInit(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + + BlockLink_t *pxBlock = (BlockLink_t *)(ptr - xHeapStructSize); + size_t oldSize = (uint16_t)(pxBlock->xBlockSize - xHeapStructSize); //size of BlockLink + heap region aligned by portBYTE_ALIGNMENT + + if (_size > oldSize && _size < xFreeBytesRemaining) + { + _size += xHeapStructSize; + + /* Ensure that blocks are always aligned to the required number + of bytes. */ + if ( ( _size & portBYTE_ALIGNMENT_MASK ) != 0x00 ) + { + /* Byte alignment required. */ + _size += ( portBYTE_ALIGNMENT - ( _size & portBYTE_ALIGNMENT_MASK ) ); + configASSERT( ( _size & portBYTE_ALIGNMENT_MASK ) == 0 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + uint8_t *newHeapRegion = (uint8_t *)pvPortMalloc(_size - xHeapStructSize); + for (uint32_t i = 0; i < _size - xHeapStructSize; i++) + { + newHeapRegion[i] = ((uint8_t *)ptr)[i]; + } + vPortFree(ptr); //libero il blocco precedentemente allocato + retVal = newHeapRegion; + + } + else if (_size < oldSize) + { + BlockLink_t *pxNewBlockLink; + _size += xHeapStructSize; + if ( ( _size & portBYTE_ALIGNMENT_MASK ) != 0x00 ) + { + /* Byte alignment required. */ + _size += ( portBYTE_ALIGNMENT - ( _size & portBYTE_ALIGNMENT_MASK ) ); + configASSERT( ( _size & portBYTE_ALIGNMENT_MASK ) == 0 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if ( (uint16_t)( pxBlock->xBlockSize - _size ) >= heapMINIMUM_BLOCK_SIZE ) //Possono essere ricavati due blocchi distinti - importantissimo il cast forzato! + { + pxNewBlockLink = ( BlockLink_t * ) ( ( ( uint8_t * ) pxBlock ) + _size); + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - _size; + pxNewBlockLink->xBlockSize &= ~xBlockAllocatedBit; + + configASSERT( ( ( ( size_t ) pxNewBlockLink ) & portBYTE_ALIGNMENT_MASK ) == 0 ); + + pxBlock->xBlockSize = _size; + pxBlock->xBlockSize |= xBlockAllocatedBit; + pxBlock->pxNextFreeBlock = NULL; + + /* Insert the new block into the list of free blocks. */ + xFreeBytesRemaining += (uint16_t)pxNewBlockLink->xBlockSize; + prvInsertBlockIntoFreeList( pxNewBlockLink ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + retVal = ptr; + + } + else //_size == oldSize + { + retVal = ptr; + } + } + (void)xTaskResumeAll(); + } + else if (ptr == NULL && _size == 0) + { + retVal = NULL; + } + + return retVal; +} + +void * pvPortCalloc(size_t nmemb, size_t _size) +{ + uint8_t *ptr = NULL; + vTaskSuspendAll(); //thread safety + { + ptr = (uint8_t *)pvPortMalloc(nmemb * _size); + for (uint32_t i = 0; i < nmemb; i++) + { + ptr[i] = 0; + } + } + (void)xTaskResumeAll(); + return (void *)ptr; +} + +#endif + +/*------------------------------------------------------------*/ +/*-------------------------WRAPPING---------------------------*/ +/*------------------------------------------------------------*/ +void * __wrap_malloc (size_t _size) +{ + return pvPortMalloc(_size); +} + +void *__real_malloc(size_t); + +/*------------------------------------------------------------*/ + +void __wrap_free (void *ptr) +{ + vPortFree(ptr); +} + +void __real_free(void *); + +/*------------------------------------------------------------*/ + +#if ENABLE_CALLOC_REALLOC + +void * __wrap_realloc (void* ptr, size_t _size) +{ + return pvPortRealloc(ptr, _size); +} + +void * __real_realloc (void *, size_t); + +/*------------------------------------------------------------*/ + +void * __wrap_calloc(size_t nmemb, size_t _size) +{ + return pvPortCalloc(nmemb, _size); +} + +void * __real_calloc(size_t, size_t); + +#endif diff --git a/lib/FreeRTOS-SAMD51/src/idle_hook.c b/lib/FreeRTOS-SAMD51/src/idle_hook.c new file mode 100644 index 0000000..1d1c725 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/idle_hook.c @@ -0,0 +1,12 @@ + +#include +#include + + +// this is referring to the loop function of your arduino project +extern void loop(void); + +void __attribute__((weak)) vApplicationIdleHook( void ) +{ + loop(); //will use your projects loop function as the rtos idle loop +} diff --git a/lib/FreeRTOS-SAMD51/src/list.c b/lib/FreeRTOS-SAMD51/src/list.c new file mode 100644 index 0000000..21dabde --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/list.c @@ -0,0 +1,198 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( List_t * const pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + pxList->xListEnd.pxPrevious = ( ListItem_t * ) &( pxList->xListEnd );/*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. */ + + pxList->uxNumberOfItems = ( UBaseType_t ) 0U; + + /* Write known values into the list if + configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ); + listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ); +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( ListItem_t * const pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pxContainer = NULL; + + /* Write known values into the list item if + configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); + listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) +{ +ListItem_t * const pxIndex = pxList->pxIndex; + + /* Only effective when configASSERT() is also defined, these tests may catch + the list data structures being overwritten in memory. They will not catch + data errors caused by incorrect configuration or use of FreeRTOS. */ + listTEST_LIST_INTEGRITY( pxList ); + listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + listGET_OWNER_OF_NEXT_ENTRY(). */ + pxNewListItem->pxNext = pxIndex; + pxNewListItem->pxPrevious = pxIndex->pxPrevious; + + /* Only used during decision coverage testing. */ + mtCOVERAGE_TEST_DELAY(); + + pxIndex->pxPrevious->pxNext = pxNewListItem; + pxIndex->pxPrevious = pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pxContainer = pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) +{ +ListItem_t *pxIterator; +const TickType_t xValueOfInsertion = pxNewListItem->xItemValue; + + /* Only effective when configASSERT() is also defined, these tests may catch + the list data structures being overwritten in memory. They will not catch + data errors caused by incorrect configuration or use of FreeRTOS. */ + listTEST_LIST_INTEGRITY( pxList ); + listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); + + /* Insert the new list item into the list, sorted in xItemValue order. + + If the list already contains a list item with the same item value then the + new list item should be placed after it. This ensures that TCBs which are + stored in ready lists (all of which have the same xItemValue value) get a + share of the CPU. However, if the xItemValue is the same as the back marker + the iteration loop below will not end. Therefore the value is checked + first, and the algorithm slightly modified if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are + listed below. In addition see https://www.freertos.org/FAQHelp.html for + more tips, and ensure configASSERT() is defined! + https://www.freertos.org/a00110.html#configASSERT + + 1) Stack overflow - + see https://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M + parts where numerically high priority values denote low actual + interrupt priorities, which can seem counter intuitive. See + https://www.freertos.org/RTOS-Cortex-M3-M4.html and the definition + of configMAX_SYSCALL_INTERRUPT_PRIORITY on + https://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended, or calling an API function that does + not end in "FromISR" from an interrupt. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + **********************************************************************/ + + for( pxIterator = ( ListItem_t * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) /*lint !e826 !e740 !e9087 The mini list structure is used as the list end to save RAM. This is checked and valid. *//*lint !e440 The iterator moves to a different value, not xValueOfInsertion. */ + { + /* There is nothing to do here, just iterating to the wanted + insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pxContainer = pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) +{ +/* The list item knows which list it is in. Obtain the list from the list +item. */ +List_t * const pxList = pxItemToRemove->pxContainer; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* Only used during decision coverage testing. */ + mtCOVERAGE_TEST_DELAY(); + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxItemToRemove->pxContainer = NULL; + ( pxList->uxNumberOfItems )--; + + return pxList->uxNumberOfItems; +} +/*-----------------------------------------------------------*/ + diff --git a/lib/FreeRTOS-SAMD51/src/list.h b/lib/FreeRTOS-SAMD51/src/list.h new file mode 100644 index 0000000..2fb6775 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/list.h @@ -0,0 +1,412 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * list_ts can only store pointers to list_item_ts. Each ListItem_t contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + +#ifndef INC_FREERTOS_H + #error FreeRTOS.h must be included before list.h +#endif + +#ifndef LIST_H +#define LIST_H + +/* + * The list structure members are modified from within interrupts, and therefore + * by rights should be declared volatile. However, they are only modified in a + * functionally atomic way (within critical sections of with the scheduler + * suspended) and are either passed by reference into a function or indexed via + * a volatile variable. Therefore, in all use cases tested so far, the volatile + * qualifier can be omitted in order to provide a moderate performance + * improvement without adversely affecting functional behaviour. The assembly + * instructions generated by the IAR, ARM and GCC compilers when the respective + * compiler's options were set for maximum optimisation has been inspected and + * deemed to be as intended. That said, as compiler technology advances, and + * especially if aggressive cross module optimisation is used (a use case that + * has not been exercised to any great extend) then it is feasible that the + * volatile qualifier will be needed for correct optimisation. It is expected + * that a compiler removing essential code because, without the volatile + * qualifier on the list structure members and with aggressive cross module + * optimisation, the compiler deemed the code unnecessary will result in + * complete and obvious failure of the scheduler. If this is ever experienced + * then the volatile qualifier can be inserted in the relevant places within the + * list structures by simply defining configLIST_VOLATILE to volatile in + * FreeRTOSConfig.h (as per the example at the bottom of this comment block). + * If configLIST_VOLATILE is not defined then the preprocessor directives below + * will simply #define configLIST_VOLATILE away completely. + * + * To use volatile list structure members then add the following line to + * FreeRTOSConfig.h (without the quotes): + * "#define configLIST_VOLATILE volatile" + */ +#ifndef configLIST_VOLATILE + #define configLIST_VOLATILE +#endif /* configSUPPORT_CROSS_MODULE_OPTIMISATION */ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Macros that can be used to place known values within the list structures, +then check that the known values do not get corrupted during the execution of +the application. These may catch the list data structures being overwritten in +memory. They will not catch data errors caused by incorrect configuration or +use of FreeRTOS.*/ +#if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 0 ) + /* Define the macros to do nothing. */ + #define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE + #define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE + #define listFIRST_LIST_INTEGRITY_CHECK_VALUE + #define listSECOND_LIST_INTEGRITY_CHECK_VALUE + #define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) + #define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) + #define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ) + #define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ) + #define listTEST_LIST_ITEM_INTEGRITY( pxItem ) + #define listTEST_LIST_INTEGRITY( pxList ) +#else + /* Define macros that add new members into the list structures. */ + #define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE TickType_t xListItemIntegrityValue1; + #define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE TickType_t xListItemIntegrityValue2; + #define listFIRST_LIST_INTEGRITY_CHECK_VALUE TickType_t xListIntegrityValue1; + #define listSECOND_LIST_INTEGRITY_CHECK_VALUE TickType_t xListIntegrityValue2; + + /* Define macros that set the new structure members to known values. */ + #define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) ( pxItem )->xListItemIntegrityValue1 = pdINTEGRITY_CHECK_VALUE + #define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ) ( pxItem )->xListItemIntegrityValue2 = pdINTEGRITY_CHECK_VALUE + #define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ) ( pxList )->xListIntegrityValue1 = pdINTEGRITY_CHECK_VALUE + #define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ) ( pxList )->xListIntegrityValue2 = pdINTEGRITY_CHECK_VALUE + + /* Define macros that will assert if one of the structure members does not + contain its expected value. */ + #define listTEST_LIST_ITEM_INTEGRITY( pxItem ) configASSERT( ( ( pxItem )->xListItemIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxItem )->xListItemIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) ) + #define listTEST_LIST_INTEGRITY( pxList ) configASSERT( ( ( pxList )->xListIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxList )->xListIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) ) +#endif /* configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES */ + + +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST; +struct xLIST_ITEM +{ + listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + configLIST_VOLATILE TickType_t xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + struct xLIST_ITEM * configLIST_VOLATILE pxNext; /*< Pointer to the next ListItem_t in the list. */ + struct xLIST_ITEM * configLIST_VOLATILE pxPrevious; /*< Pointer to the previous ListItem_t in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + struct xLIST * configLIST_VOLATILE pxContainer; /*< Pointer to the list in which this list item is placed (if any). */ + listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ +}; +typedef struct xLIST_ITEM ListItem_t; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + configLIST_VOLATILE TickType_t xItemValue; + struct xLIST_ITEM * configLIST_VOLATILE pxNext; + struct xLIST_ITEM * configLIST_VOLATILE pxPrevious; +}; +typedef struct xMINI_LIST_ITEM MiniListItem_t; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + listFIRST_LIST_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ + volatile UBaseType_t uxNumberOfItems; + ListItem_t * configLIST_VOLATILE pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to listGET_OWNER_OF_NEXT_ENTRY (). */ + MiniListItem_t xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ + listSECOND_LIST_INTEGRITY_CHECK_VALUE /*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ +} List_t; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) ) + +/* + * Access macro to get the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_OWNER( pxListItem ) ( ( pxListItem )->pvOwner ) + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( ( pxListItem )->xItemValue = ( xValue ) ) + +/* + * Access macro to retrieve the value of the list item. The value can + * represent anything - for example the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro to retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( ( ( pxList )->xListEnd ).pxNext->xItemValue ) + +/* + * Return the list item at the head of the list. + * + * \page listGET_HEAD_ENTRY listGET_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_HEAD_ENTRY( pxList ) ( ( ( pxList )->xListEnd ).pxNext ) + +/* + * Return the list item at the head of the list. + * + * \page listGET_NEXT listGET_NEXT + * \ingroup LinkedList + */ +#define listGET_NEXT( pxListItem ) ( ( pxListItem )->pxNext ) + +/* + * Return the list item that marks the end of the list + * + * \page listGET_END_MARKER listGET_END_MARKER + * \ingroup LinkedList + */ +#define listGET_END_MARKER( pxList ) ( ( ListItem_t const * ) ( &( ( pxList )->xListEnd ) ) ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( ( pxList )->uxNumberOfItems == ( UBaseType_t ) 0 ) ? pdTRUE : pdFALSE ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entry's pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxTCB pxTCB is set to the address of the owner of the next list item. + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +List_t * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( void * ) ( pxConstList )->pxIndex == ( void * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE if the list item is in the list, otherwise pdFALSE. + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( ( pxListItem )->pxContainer == ( pxList ) ) ? ( pdTRUE ) : ( pdFALSE ) ) + +/* + * Return the list a list item is contained within (referenced from). + * + * @param pxListItem The list item being queried. + * @return A pointer to the List_t object that references the pxListItem + */ +#define listLIST_ITEM_CONTAINER( pxListItem ) ( ( pxListItem )->pxContainer ) + +/* + * This provides a crude means of knowing if a list has been initialised, as + * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() + * function. + */ +#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( List_t * const pxList ) PRIVILEGED_FUNCTION; + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( ListItem_t * const pxItem ) PRIVILEGED_FUNCTION; + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION; + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pxIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pxIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION; + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param uxListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * @return The number of items that remain in the list after the list item has + * been removed. + * + * \page uxListRemove uxListRemove + * \ingroup LinkedList + */ +UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/lib/FreeRTOS-SAMD51/src/message_buffer.h b/lib/FreeRTOS-SAMD51/src/message_buffer.h new file mode 100644 index 0000000..cfa08cb --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/message_buffer.h @@ -0,0 +1,799 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +/* + * Message buffers build functionality on top of FreeRTOS stream buffers. + * Whereas stream buffers are used to send a continuous stream of data from one + * task or interrupt to another, message buffers are used to send variable + * length discrete messages from one task or interrupt to another. Their + * implementation is light weight, making them particularly suited for interrupt + * to task and core to core communication scenarios. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * timeout to 0. + * + * Message buffers hold variable length messages. To enable that, when a + * message is written to the message buffer an additional sizeof( size_t ) bytes + * are also written to store the message's length (that happens internally, with + * the API function). sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so writing a 10 byte message to a message buffer on a 32-bit + * architecture will actually reduce the available space in the message buffer + * by 14 bytes (10 byte are used by the message, and 4 bytes to hold the length + * of the message). + */ + +#ifndef FREERTOS_MESSAGE_BUFFER_H +#define FREERTOS_MESSAGE_BUFFER_H + +/* Message buffers are built onto of stream buffers. */ +#include "stream_buffer.h" + +#if defined( __cplusplus ) +extern "C" { +#endif + +/** + * Type by which message buffers are referenced. For example, a call to + * xMessageBufferCreate() returns an MessageBufferHandle_t variable that can + * then be used as a parameter to xMessageBufferSend(), xMessageBufferReceive(), + * etc. + */ +typedef void * MessageBufferHandle_t; + +/*-----------------------------------------------------------*/ + +/** + * message_buffer.h + * +
+MessageBufferHandle_t xMessageBufferCreate( size_t xBufferSizeBytes );
+
+ * + * Creates a new message buffer using dynamically allocated memory. See + * xMessageBufferCreateStatic() for a version that uses statically allocated + * memory (memory that is allocated at compile time). + * + * configSUPPORT_DYNAMIC_ALLOCATION must be set to 1 or left undefined in + * FreeRTOSConfig.h for xMessageBufferCreate() to be available. + * + * @param xBufferSizeBytes The total number of bytes (not messages) the message + * buffer will be able to hold at any one time. When a message is written to + * the message buffer an additional sizeof( size_t ) bytes are also written to + * store the message's length. sizeof( size_t ) is typically 4 bytes on a + * 32-bit architecture, so on most 32-bit architectures a 10 byte message will + * take up 14 bytes of message buffer space. + * + * @return If NULL is returned, then the message buffer cannot be created + * because there is insufficient heap memory available for FreeRTOS to allocate + * the message buffer data structures and storage area. A non-NULL value being + * returned indicates that the message buffer has been created successfully - + * the returned value should be stored as the handle to the created message + * buffer. + * + * Example use: +
+
+void vAFunction( void )
+{
+MessageBufferHandle_t xMessageBuffer;
+const size_t xMessageBufferSizeBytes = 100;
+
+    // Create a message buffer that can hold 100 bytes.  The memory used to hold
+    // both the message buffer structure and the messages themselves is allocated
+    // dynamically.  Each message added to the buffer consumes an additional 4
+    // bytes which are used to hold the lengh of the message.
+    xMessageBuffer = xMessageBufferCreate( xMessageBufferSizeBytes );
+
+    if( xMessageBuffer == NULL )
+    {
+        // There was not enough heap memory space available to create the
+        // message buffer.
+    }
+    else
+    {
+        // The message buffer was created successfully and can now be used.
+    }
+
+
+ * \defgroup xMessageBufferCreate xMessageBufferCreate + * \ingroup MessageBufferManagement + */ +#define xMessageBufferCreate( xBufferSizeBytes ) ( MessageBufferHandle_t ) xStreamBufferGenericCreate( xBufferSizeBytes, ( size_t ) 0, pdTRUE ) + +/** + * message_buffer.h + * +
+MessageBufferHandle_t xMessageBufferCreateStatic( size_t xBufferSizeBytes,
+                                                  uint8_t *pucMessageBufferStorageArea,
+                                                  StaticMessageBuffer_t *pxStaticMessageBuffer );
+
+ * Creates a new message buffer using statically allocated memory. See + * xMessageBufferCreate() for a version that uses dynamically allocated memory. + * + * @param xBufferSizeBytes The size, in bytes, of the buffer pointed to by the + * pucMessageBufferStorageArea parameter. When a message is written to the + * message buffer an additional sizeof( size_t ) bytes are also written to store + * the message's length. sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so on most 32-bit architecture a 10 byte message will take up + * 14 bytes of message buffer space. The maximum number of bytes that can be + * stored in the message buffer is actually (xBufferSizeBytes - 1). + * + * @param pucMessageBufferStorageArea Must point to a uint8_t array that is at + * least xBufferSizeBytes + 1 big. This is the array to which messages are + * copied when they are written to the message buffer. + * + * @param pxStaticMessageBuffer Must point to a variable of type + * StaticMessageBuffer_t, which will be used to hold the message buffer's data + * structure. + * + * @return If the message buffer is created successfully then a handle to the + * created message buffer is returned. If either pucMessageBufferStorageArea or + * pxStaticmessageBuffer are NULL then NULL is returned. + * + * Example use: +
+
+// Used to dimension the array used to hold the messages.  The available space
+// will actually be one less than this, so 999.
+#define STORAGE_SIZE_BYTES 1000
+
+// Defines the memory that will actually hold the messages within the message
+// buffer.
+static uint8_t ucStorageBuffer[ STORAGE_SIZE_BYTES ];
+
+// The variable used to hold the message buffer structure.
+StaticMessageBuffer_t xMessageBufferStruct;
+
+void MyFunction( void )
+{
+MessageBufferHandle_t xMessageBuffer;
+
+    xMessageBuffer = xMessageBufferCreateStatic( sizeof( ucBufferStorage ),
+                                                 ucBufferStorage,
+                                                 &xMessageBufferStruct );
+
+    // As neither the pucMessageBufferStorageArea or pxStaticMessageBuffer
+    // parameters were NULL, xMessageBuffer will not be NULL, and can be used to
+    // reference the created message buffer in other message buffer API calls.
+
+    // Other code that uses the message buffer can go here.
+}
+
+
+ * \defgroup xMessageBufferCreateStatic xMessageBufferCreateStatic + * \ingroup MessageBufferManagement + */ +#define xMessageBufferCreateStatic( xBufferSizeBytes, pucMessageBufferStorageArea, pxStaticMessageBuffer ) ( MessageBufferHandle_t ) xStreamBufferGenericCreateStatic( xBufferSizeBytes, 0, pdTRUE, pucMessageBufferStorageArea, pxStaticMessageBuffer ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferSend( MessageBufferHandle_t xMessageBuffer,
+                           const void *pvTxData,
+                           size_t xDataLengthBytes,
+                           TickType_t xTicksToWait );
+
+ *
+ * Sends a discrete message to the message buffer.  The message can be any
+ * length that fits within the buffer's free space, and is copied into the
+ * buffer.
+ *
+ * ***NOTE***:  Uniquely among FreeRTOS objects, the stream buffer
+ * implementation (so also the message buffer implementation, as message buffers
+ * are built on top of stream buffers) assumes there is only one task or
+ * interrupt that will write to the buffer (the writer), and only one task or
+ * interrupt that will read from the buffer (the reader).  It is safe for the
+ * writer and reader to be different tasks or interrupts, but, unlike other
+ * FreeRTOS objects, it is not safe to have multiple different writers or
+ * multiple different readers.  If there are to be multiple different writers
+ * then the application writer must place each call to a writing API function
+ * (such as xMessageBufferSend()) inside a critical section and set the send
+ * block time to 0.  Likewise, if there are to be multiple different readers
+ * then the application writer must place each call to a reading API function
+ * (such as xMessageBufferRead()) inside a critical section and set the receive
+ * block time to 0.
+ *
+ * Use xMessageBufferSend() to write to a message buffer from a task.  Use
+ * xMessageBufferSendFromISR() to write to a message buffer from an interrupt
+ * service routine (ISR).
+ *
+ * @param xMessageBuffer The handle of the message buffer to which a message is
+ * being sent.
+ *
+ * @param pvTxData A pointer to the message that is to be copied into the
+ * message buffer.
+ *
+ * @param xDataLengthBytes The length of the message.  That is, the number of
+ * bytes to copy from pvTxData into the message buffer.  When a message is
+ * written to the message buffer an additional sizeof( size_t ) bytes are also
+ * written to store the message's length.  sizeof( size_t ) is typically 4 bytes
+ * on a 32-bit architecture, so on most 32-bit architecture setting
+ * xDataLengthBytes to 20 will reduce the free space in the message buffer by 24
+ * bytes (20 bytes of message data and 4 bytes to hold the message length).
+ *
+ * @param xTicksToWait The maximum amount of time the calling task should remain
+ * in the Blocked state to wait for enough space to become available in the
+ * message buffer, should the message buffer have insufficient space when
+ * xMessageBufferSend() is called.  The calling task will never block if
+ * xTicksToWait is zero.  The block time is specified in tick periods, so the
+ * absolute time it represents is dependent on the tick frequency.  The macro
+ * pdMS_TO_TICKS() can be used to convert a time specified in milliseconds into
+ * a time specified in ticks.  Setting xTicksToWait to portMAX_DELAY will cause
+ * the task to wait indefinitely (without timing out), provided
+ * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h.  Tasks do not use any
+ * CPU time when they are in the Blocked state.
+ *
+ * @return The number of bytes written to the message buffer.  If the call to
+ * xMessageBufferSend() times out before there was enough space to write the
+ * message into the message buffer then zero is returned.  If the call did not
+ * time out then xDataLengthBytes is returned.
+ *
+ * Example use:
+
+void vAFunction( MessageBufferHandle_t xMessageBuffer )
+{
+size_t xBytesSent;
+uint8_t ucArrayToSend[] = { 0, 1, 2, 3 };
+char *pcStringToSend = "String to send";
+const TickType_t x100ms = pdMS_TO_TICKS( 100 );
+
+    // Send an array to the message buffer, blocking for a maximum of 100ms to
+    // wait for enough space to be available in the message buffer.
+    xBytesSent = xMessageBufferSend( xMessageBuffer, ( void * ) ucArrayToSend, sizeof( ucArrayToSend ), x100ms );
+
+    if( xBytesSent != sizeof( ucArrayToSend ) )
+    {
+        // The call to xMessageBufferSend() times out before there was enough
+        // space in the buffer for the data to be written.
+    }
+
+    // Send the string to the message buffer.  Return immediately if there is
+    // not enough space in the buffer.
+    xBytesSent = xMessageBufferSend( xMessageBuffer, ( void * ) pcStringToSend, strlen( pcStringToSend ), 0 );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The string could not be added to the message buffer because there was
+        // not enough free space in the buffer.
+    }
+}
+
+ * \defgroup xMessageBufferSend xMessageBufferSend + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSend( xMessageBuffer, pvTxData, xDataLengthBytes, xTicksToWait ) xStreamBufferSend( ( StreamBufferHandle_t ) xMessageBuffer, pvTxData, xDataLengthBytes, xTicksToWait ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferSendFromISR( MessageBufferHandle_t xMessageBuffer,
+                                  const void *pvTxData,
+                                  size_t xDataLengthBytes,
+                                  BaseType_t *pxHigherPriorityTaskWoken );
+
+ *
+ * Interrupt safe version of the API function that sends a discrete message to
+ * the message buffer.  The message can be any length that fits within the
+ * buffer's free space, and is copied into the buffer.
+ *
+ * ***NOTE***:  Uniquely among FreeRTOS objects, the stream buffer
+ * implementation (so also the message buffer implementation, as message buffers
+ * are built on top of stream buffers) assumes there is only one task or
+ * interrupt that will write to the buffer (the writer), and only one task or
+ * interrupt that will read from the buffer (the reader).  It is safe for the
+ * writer and reader to be different tasks or interrupts, but, unlike other
+ * FreeRTOS objects, it is not safe to have multiple different writers or
+ * multiple different readers.  If there are to be multiple different writers
+ * then the application writer must place each call to a writing API function
+ * (such as xMessageBufferSend()) inside a critical section and set the send
+ * block time to 0.  Likewise, if there are to be multiple different readers
+ * then the application writer must place each call to a reading API function
+ * (such as xMessageBufferRead()) inside a critical section and set the receive
+ * block time to 0.
+ *
+ * Use xMessageBufferSend() to write to a message buffer from a task.  Use
+ * xMessageBufferSendFromISR() to write to a message buffer from an interrupt
+ * service routine (ISR).
+ *
+ * @param xMessageBuffer The handle of the message buffer to which a message is
+ * being sent.
+ *
+ * @param pvTxData A pointer to the message that is to be copied into the
+ * message buffer.
+ *
+ * @param xDataLengthBytes The length of the message.  That is, the number of
+ * bytes to copy from pvTxData into the message buffer.  When a message is
+ * written to the message buffer an additional sizeof( size_t ) bytes are also
+ * written to store the message's length.  sizeof( size_t ) is typically 4 bytes
+ * on a 32-bit architecture, so on most 32-bit architecture setting
+ * xDataLengthBytes to 20 will reduce the free space in the message buffer by 24
+ * bytes (20 bytes of message data and 4 bytes to hold the message length).
+ *
+ * @param pxHigherPriorityTaskWoken  It is possible that a message buffer will
+ * have a task blocked on it waiting for data.  Calling
+ * xMessageBufferSendFromISR() can make data available, and so cause a task that
+ * was waiting for data to leave the Blocked state.  If calling
+ * xMessageBufferSendFromISR() causes a task to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently executing task (the
+ * task that was interrupted), then, internally, xMessageBufferSendFromISR()
+ * will set *pxHigherPriorityTaskWoken to pdTRUE.  If
+ * xMessageBufferSendFromISR() sets this value to pdTRUE, then normally a
+ * context switch should be performed before the interrupt is exited.  This will
+ * ensure that the interrupt returns directly to the highest priority Ready
+ * state task.  *pxHigherPriorityTaskWoken should be set to pdFALSE before it
+ * is passed into the function.  See the code example below for an example.
+ *
+ * @return The number of bytes actually written to the message buffer.  If the
+ * message buffer didn't have enough free space for the message to be stored
+ * then 0 is returned, otherwise xDataLengthBytes is returned.
+ *
+ * Example use:
+
+// A message buffer that has already been created.
+MessageBufferHandle_t xMessageBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+size_t xBytesSent;
+char *pcStringToSend = "String to send";
+BaseType_t xHigherPriorityTaskWoken = pdFALSE; // Initialised to pdFALSE.
+
+    // Attempt to send the string to the message buffer.
+    xBytesSent = xMessageBufferSendFromISR( xMessageBuffer,
+                                            ( void * ) pcStringToSend,
+                                            strlen( pcStringToSend ),
+                                            &xHigherPriorityTaskWoken );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The string could not be added to the message buffer because there was
+        // not enough free space in the buffer.
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xMessageBufferSendFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xMessageBufferSendFromISR xMessageBufferSendFromISR + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSendFromISR( xMessageBuffer, pvTxData, xDataLengthBytes, pxHigherPriorityTaskWoken ) xStreamBufferSendFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pvTxData, xDataLengthBytes, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+size_t xMessageBufferReceive( MessageBufferHandle_t xMessageBuffer,
+                              void *pvRxData,
+                              size_t xBufferLengthBytes,
+                              TickType_t xTicksToWait );
+
+ * + * Receives a discrete message from a message buffer. Messages can be of + * variable length and are copied out of the buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xMessageBufferReceive() to read from a message buffer from a task. Use + * xMessageBufferReceiveFromISR() to read from a message buffer from an + * interrupt service routine (ISR). + * + * @param xMessageBuffer The handle of the message buffer from which a message + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received message is + * to be copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the pvRxData + * parameter. This sets the maximum length of the message that can be received. + * If xBufferLengthBytes is too small to hold the next message then the message + * will be left in the message buffer and 0 will be returned. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for a message, should the message buffer be empty. + * xMessageBufferReceive() will return immediately if xTicksToWait is zero and + * the message buffer is empty. The block time is specified in tick periods, so + * the absolute time it represents is dependent on the tick frequency. The + * macro pdMS_TO_TICKS() can be used to convert a time specified in milliseconds + * into a time specified in ticks. Setting xTicksToWait to portMAX_DELAY will + * cause the task to wait indefinitely (without timing out), provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h. Tasks do not use any + * CPU time when they are in the Blocked state. + * + * @return The length, in bytes, of the message read from the message buffer, if + * any. If xMessageBufferReceive() times out before a message became available + * then zero is returned. If the length of the message is greater than + * xBufferLengthBytes then the message will be left in the message buffer and + * zero is returned. + * + * Example use: +
+void vAFunction( MessageBuffer_t xMessageBuffer )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+const TickType_t xBlockTime = pdMS_TO_TICKS( 20 );
+
+    // Receive the next message from the message buffer.  Wait in the Blocked
+    // state (so not using any CPU processing time) for a maximum of 100ms for
+    // a message to become available.
+    xReceivedBytes = xMessageBufferReceive( xMessageBuffer,
+                                            ( void * ) ucRxData,
+                                            sizeof( ucRxData ),
+                                            xBlockTime );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains a message that is xReceivedBytes long.  Process
+        // the message here....
+    }
+}
+
+ * \defgroup xMessageBufferReceive xMessageBufferReceive + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReceive( xMessageBuffer, pvRxData, xBufferLengthBytes, xTicksToWait ) xStreamBufferReceive( ( StreamBufferHandle_t ) xMessageBuffer, pvRxData, xBufferLengthBytes, xTicksToWait ) + + +/** + * message_buffer.h + * +
+size_t xMessageBufferReceiveFromISR( MessageBufferHandle_t xMessageBuffer,
+                                     void *pvRxData,
+                                     size_t xBufferLengthBytes,
+                                     BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * An interrupt safe version of the API function that receives a discrete + * message from a message buffer. Messages can be of variable length and are + * copied out of the buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xMessageBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xMessageBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xMessageBufferReceive() to read from a message buffer from a task. Use + * xMessageBufferReceiveFromISR() to read from a message buffer from an + * interrupt service routine (ISR). + * + * @param xMessageBuffer The handle of the message buffer from which a message + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received message is + * to be copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the pvRxData + * parameter. This sets the maximum length of the message that can be received. + * If xBufferLengthBytes is too small to hold the next message then the message + * will be left in the message buffer and 0 will be returned. + * + * @param pxHigherPriorityTaskWoken It is possible that a message buffer will + * have a task blocked on it waiting for space to become available. Calling + * xMessageBufferReceiveFromISR() can make space available, and so cause a task + * that is waiting for space to leave the Blocked state. If calling + * xMessageBufferReceiveFromISR() causes a task to leave the Blocked state, and + * the unblocked task has a priority higher than the currently executing task + * (the task that was interrupted), then, internally, + * xMessageBufferReceiveFromISR() will set *pxHigherPriorityTaskWoken to pdTRUE. + * If xMessageBufferReceiveFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. That will + * ensure the interrupt returns directly to the highest priority Ready state + * task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it is + * passed into the function. See the code example below for an example. + * + * @return The length, in bytes, of the message read from the message buffer, if + * any. + * + * Example use: +
+// A message buffer that has already been created.
+MessageBuffer_t xMessageBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;  // Initialised to pdFALSE.
+
+    // Receive the next message from the message buffer.
+    xReceivedBytes = xMessageBufferReceiveFromISR( xMessageBuffer,
+                                                  ( void * ) ucRxData,
+                                                  sizeof( ucRxData ),
+                                                  &xHigherPriorityTaskWoken );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains a message that is xReceivedBytes long.  Process
+        // the message here....
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xMessageBufferReceiveFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xMessageBufferReceiveFromISR xMessageBufferReceiveFromISR + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReceiveFromISR( xMessageBuffer, pvRxData, xBufferLengthBytes, pxHigherPriorityTaskWoken ) xStreamBufferReceiveFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pvRxData, xBufferLengthBytes, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+void vMessageBufferDelete( MessageBufferHandle_t xMessageBuffer );
+
+ * + * Deletes a message buffer that was previously created using a call to + * xMessageBufferCreate() or xMessageBufferCreateStatic(). If the message + * buffer was created using dynamic memory (that is, by xMessageBufferCreate()), + * then the allocated memory is freed. + * + * A message buffer handle must not be used after the message buffer has been + * deleted. + * + * @param xMessageBuffer The handle of the message buffer to be deleted. + * + */ +#define vMessageBufferDelete( xMessageBuffer ) vStreamBufferDelete( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferIsFull( MessageBufferHandle_t xMessageBuffer ) );
+
+ * + * Tests to see if a message buffer is full. A message buffer is full if it + * cannot accept any more messages, of any size, until space is made available + * by a message being removed from the message buffer. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return If the message buffer referenced by xMessageBuffer is full then + * pdTRUE is returned. Otherwise pdFALSE is returned. + */ +#define xMessageBufferIsFull( xMessageBuffer ) xStreamBufferIsFull( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferIsEmpty( MessageBufferHandle_t xMessageBuffer ) );
+
+ * + * Tests to see if a message buffer is empty (does not contain any messages). + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return If the message buffer referenced by xMessageBuffer is empty then + * pdTRUE is returned. Otherwise pdFALSE is returned. + * + */ +#define xMessageBufferIsEmpty( xMessageBuffer ) xStreamBufferIsEmpty( ( StreamBufferHandle_t ) xMessageBuffer ) + +/** + * message_buffer.h +
+BaseType_t xMessageBufferReset( MessageBufferHandle_t xMessageBuffer );
+
+ * + * Resets a message buffer to its initial empty state, discarding any message it + * contained. + * + * A message buffer can only be reset if there are no tasks blocked on it. + * + * @param xMessageBuffer The handle of the message buffer being reset. + * + * @return If the message buffer was reset then pdPASS is returned. If the + * message buffer could not be reset because either there was a task blocked on + * the message queue to wait for space to become available, or to wait for a + * a message to be available, then pdFAIL is returned. + * + * \defgroup xMessageBufferReset xMessageBufferReset + * \ingroup MessageBufferManagement + */ +#define xMessageBufferReset( xMessageBuffer ) xStreamBufferReset( ( StreamBufferHandle_t ) xMessageBuffer ) + + +/** + * message_buffer.h +
+size_t xMessageBufferSpaceAvailable( MessageBufferHandle_t xMessageBuffer ) );
+
+ * Returns the number of bytes of free space in the message buffer. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return The number of bytes that can be written to the message buffer before + * the message buffer would be full. When a message is written to the message + * buffer an additional sizeof( size_t ) bytes are also written to store the + * message's length. sizeof( size_t ) is typically 4 bytes on a 32-bit + * architecture, so if xMessageBufferSpacesAvailable() returns 10, then the size + * of the largest message that can be written to the message buffer is 6 bytes. + * + * \defgroup xMessageBufferSpaceAvailable xMessageBufferSpaceAvailable + * \ingroup MessageBufferManagement + */ +#define xMessageBufferSpaceAvailable( xMessageBuffer ) xStreamBufferSpacesAvailable( ( StreamBufferHandle_t ) xMessageBuffer ) +#define xMessageBufferSpacesAvailable( xMessageBuffer ) xStreamBufferSpacesAvailable( ( StreamBufferHandle_t ) xMessageBuffer ) /* Corrects typo in original macro name. */ + +/** + * message_buffer.h +
+ size_t xMessageBufferNextLengthBytes( MessageBufferHandle_t xMessageBuffer ) );
+ 
+ * Returns the length (in bytes) of the next message in a message buffer. + * Useful if xMessageBufferReceive() returned 0 because the size of the buffer + * passed into xMessageBufferReceive() was too small to hold the next message. + * + * @param xMessageBuffer The handle of the message buffer being queried. + * + * @return The length (in bytes) of the next message in the message buffer, or 0 + * if the message buffer is empty. + * + * \defgroup xMessageBufferNextLengthBytes xMessageBufferNextLengthBytes + * \ingroup MessageBufferManagement + */ +#define xMessageBufferNextLengthBytes( xMessageBuffer ) xStreamBufferNextMessageLengthBytes( ( StreamBufferHandle_t ) xMessageBuffer ) PRIVILEGED_FUNCTION; + +/** + * message_buffer.h + * +
+BaseType_t xMessageBufferSendCompletedFromISR( MessageBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbSEND_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is sent to a message buffer or stream buffer. If there was a task that + * was blocked on the message or stream buffer waiting for data to arrive then + * the sbSEND_COMPLETED() macro sends a notification to the task to remove it + * from the Blocked state. xMessageBufferSendCompletedFromISR() does the same + * thing. It is provided to enable application writers to implement their own + * version of sbSEND_COMPLETED(), and MUST NOT BE USED AT ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer to which data was + * written. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xMessageBufferSendCompletedFromISR(). If calling + * xMessageBufferSendCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xMessageBufferSendCompletedFromISR xMessageBufferSendCompletedFromISR + * \ingroup StreamBufferManagement + */ +#define xMessageBufferSendCompletedFromISR( xMessageBuffer, pxHigherPriorityTaskWoken ) xStreamBufferSendCompletedFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pxHigherPriorityTaskWoken ) + +/** + * message_buffer.h + * +
+BaseType_t xMessageBufferReceiveCompletedFromISR( MessageBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbRECEIVE_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is read out of a message buffer or stream buffer. If there was a task + * that was blocked on the message or stream buffer waiting for data to arrive + * then the sbRECEIVE_COMPLETED() macro sends a notification to the task to + * remove it from the Blocked state. xMessageBufferReceiveCompletedFromISR() + * does the same thing. It is provided to enable application writers to + * implement their own version of sbRECEIVE_COMPLETED(), and MUST NOT BE USED AT + * ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer from which data was + * read. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xMessageBufferReceiveCompletedFromISR(). If calling + * xMessageBufferReceiveCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xMessageBufferReceiveCompletedFromISR xMessageBufferReceiveCompletedFromISR + * \ingroup StreamBufferManagement + */ +#define xMessageBufferReceiveCompletedFromISR( xMessageBuffer, pxHigherPriorityTaskWoken ) xStreamBufferReceiveCompletedFromISR( ( StreamBufferHandle_t ) xMessageBuffer, pxHigherPriorityTaskWoken ) + +#if defined( __cplusplus ) +} /* extern "C" */ +#endif + +#endif /* !defined( FREERTOS_MESSAGE_BUFFER_H ) */ diff --git a/lib/FreeRTOS-SAMD51/src/mpu_prototypes.h b/lib/FreeRTOS-SAMD51/src/mpu_prototypes.h new file mode 100644 index 0000000..5d74907 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/mpu_prototypes.h @@ -0,0 +1,157 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* + * When the MPU is used the standard (non MPU) API functions are mapped to + * equivalents that start "MPU_", the prototypes for which are defined in this + * header files. This will cause the application code to call the MPU_ version + * which wraps the non-MPU version with privilege promoting then demoting code, + * so the kernel code always runs will full privileges. + */ + + +#ifndef MPU_PROTOTYPES_H +#define MPU_PROTOTYPES_H + +/* MPU versions of tasks.h API functions. */ +BaseType_t MPU_xTaskCreate( TaskFunction_t pxTaskCode, const char * const pcName, const uint16_t usStackDepth, void * const pvParameters, UBaseType_t uxPriority, TaskHandle_t * const pxCreatedTask ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskCreateStatic( TaskFunction_t pxTaskCode, const char * const pcName, const uint32_t ulStackDepth, void * const pvParameters, UBaseType_t uxPriority, StackType_t * const puxStackBuffer, StaticTask_t * const pxTaskBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelete( TaskHandle_t xTaskToDelete ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelay( const TickType_t xTicksToDelay ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskAbortDelay( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskPriorityGet( const TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +eTaskState MPU_eTaskGetState( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSuspend( TaskHandle_t xTaskToSuspend ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskResume( TaskHandle_t xTaskToResume ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskStartScheduler( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSuspendAll( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskResumeAll( void ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTaskGetTickCount( void ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetNumberOfTasks( void ) FREERTOS_SYSTEM_CALL; +char * MPU_pcTaskGetName( TaskHandle_t xTaskToQuery ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetHandle( const char *pcNameToQuery ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +configSTACK_DEPTH_TYPE MPU_uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) FREERTOS_SYSTEM_CALL; +TaskHookFunction_t MPU_xTaskGetApplicationTaskTag( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) FREERTOS_SYSTEM_CALL; +void * MPU_pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetIdleTaskHandle( void ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTaskGetIdleRunTimeCounter( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskList( char * pcWriteBuffer ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskGetRunTimeStats( char *pcWriteBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +uint32_t MPU_ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskNotifyStateClear( TaskHandle_t xTask ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskIncrementTick( void ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTaskGetCurrentTaskHandle( void ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) FREERTOS_SYSTEM_CALL; +void MPU_vTaskMissedYield( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTaskGetSchedulerState( void ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of queue.h API functions. */ +BaseType_t MPU_xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueMessagesWaiting( const QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueSpacesAvailable( const QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueDelete( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateMutex( const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xQueueGetMutexHolder( QueueHandle_t xSemaphore ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueGiveMutexRecursive( QueueHandle_t pxMutex ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcName ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueUnregisterQueue( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +const char * MPU_pcQueueGetName( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueHandle_t MPU_xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) FREERTOS_SYSTEM_CALL; +QueueSetHandle_t MPU_xQueueCreateSet( const UBaseType_t uxEventQueueLength ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) FREERTOS_SYSTEM_CALL; +QueueSetMemberHandle_t MPU_xQueueSelectFromSet( QueueSetHandle_t xQueueSet, const TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) FREERTOS_SYSTEM_CALL; +void MPU_vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxQueueGetQueueNumber( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; +uint8_t MPU_ucQueueGetQueueType( QueueHandle_t xQueue ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of timers.h API functions. */ +TimerHandle_t MPU_xTimerCreate( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction ) FREERTOS_SYSTEM_CALL; +TimerHandle_t MPU_xTimerCreateStatic( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction, StaticTimer_t *pxTimerBuffer ) FREERTOS_SYSTEM_CALL; +void * MPU_pvTimerGetTimerID( const TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +void MPU_vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerIsTimerActive( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +TaskHandle_t MPU_xTimerGetTimerDaemonTaskHandle( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +const char * MPU_pcTimerGetName( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +void MPU_vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTimerGetPeriod( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +TickType_t MPU_xTimerGetExpiryTime( TimerHandle_t xTimer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerCreateTimerTask( void ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of event_group.h API functions. */ +EventGroupHandle_t MPU_xEventGroupCreate( void ) FREERTOS_SYSTEM_CALL; +EventGroupHandle_t MPU_xEventGroupCreateStatic( StaticEventGroup_t *pxEventGroupBuffer ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) FREERTOS_SYSTEM_CALL; +EventBits_t MPU_xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +void MPU_vEventGroupDelete( EventGroupHandle_t xEventGroup ) FREERTOS_SYSTEM_CALL; +UBaseType_t MPU_uxEventGroupGetNumber( void* xEventGroup ) FREERTOS_SYSTEM_CALL; + +/* MPU versions of message/stream_buffer.h API functions. */ +size_t MPU_xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, const void *pvTxData, size_t xDataLengthBytes, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, void *pvRxData, size_t xBufferLengthBytes, TickType_t xTicksToWait ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +void MPU_vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +size_t MPU_xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) FREERTOS_SYSTEM_CALL; +BaseType_t MPU_xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) FREERTOS_SYSTEM_CALL; +StreamBufferHandle_t MPU_xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer ) FREERTOS_SYSTEM_CALL; +StreamBufferHandle_t MPU_xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer, uint8_t * const pucStreamBufferStorageArea, StaticStreamBuffer_t * const pxStaticStreamBuffer ) FREERTOS_SYSTEM_CALL; + + + +#endif /* MPU_PROTOTYPES_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/mpu_wrappers.h b/lib/FreeRTOS-SAMD51/src/mpu_wrappers.h new file mode 100644 index 0000000..711393f --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/mpu_wrappers.h @@ -0,0 +1,186 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + /* + * Map standard (non MPU) API functions to equivalents that start + * "MPU_". This will cause the application code to call the MPU_ + * version, which wraps the non-MPU version with privilege promoting + * then demoting code, so the kernel code always runs will full + * privileges. + */ + + /* Map standard tasks.h API functions to the MPU equivalents. */ + #define xTaskCreate MPU_xTaskCreate + #define xTaskCreateStatic MPU_xTaskCreateStatic + #define xTaskCreateRestricted MPU_xTaskCreateRestricted + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelay MPU_vTaskDelay + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define xTaskAbortDelay MPU_xTaskAbortDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define eTaskGetState MPU_eTaskGetState + #define vTaskGetInfo MPU_vTaskGetInfo + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define pcTaskGetName MPU_pcTaskGetName + #define xTaskGetHandle MPU_xTaskGetHandle + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define uxTaskGetStackHighWaterMark2 MPU_uxTaskGetStackHighWaterMark2 + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define vTaskSetThreadLocalStoragePointer MPU_vTaskSetThreadLocalStoragePointer + #define pvTaskGetThreadLocalStoragePointer MPU_pvTaskGetThreadLocalStoragePointer + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define xTaskGetIdleTaskHandle MPU_xTaskGetIdleTaskHandle + #define uxTaskGetSystemState MPU_uxTaskGetSystemState + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define xTaskGetIdleRunTimeCounter MPU_xTaskGetIdleRunTimeCounter + #define xTaskGenericNotify MPU_xTaskGenericNotify + #define xTaskNotifyWait MPU_xTaskNotifyWait + #define ulTaskNotifyTake MPU_ulTaskNotifyTake + #define xTaskNotifyStateClear MPU_xTaskNotifyStateClear + + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define vTaskSetTimeOutState MPU_vTaskSetTimeOutState + #define xTaskCheckForTimeOut MPU_xTaskCheckForTimeOut + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + /* Map standard queue.h API functions to the MPU equivalents. */ + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueReceive MPU_xQueueReceive + #define xQueuePeek MPU_xQueuePeek + #define xQueueSemaphoreTake MPU_xQueueSemaphoreTake + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define uxQueueSpacesAvailable MPU_uxQueueSpacesAvailable + #define vQueueDelete MPU_vQueueDelete + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueCreateMutexStatic MPU_xQueueCreateMutexStatic + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueCreateCountingSemaphoreStatic MPU_xQueueCreateCountingSemaphoreStatic + #define xQueueGetMutexHolder MPU_xQueueGetMutexHolder + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueGenericCreate MPU_xQueueGenericCreate + #define xQueueGenericCreateStatic MPU_xQueueGenericCreateStatic + #define xQueueCreateSet MPU_xQueueCreateSet + #define xQueueAddToSet MPU_xQueueAddToSet + #define xQueueRemoveFromSet MPU_xQueueRemoveFromSet + #define xQueueSelectFromSet MPU_xQueueSelectFromSet + #define xQueueGenericReset MPU_xQueueGenericReset + + #if( configQUEUE_REGISTRY_SIZE > 0 ) + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #define pcQueueGetName MPU_pcQueueGetName + #endif + + /* Map standard timer.h API functions to the MPU equivalents. */ + #define xTimerCreate MPU_xTimerCreate + #define xTimerCreateStatic MPU_xTimerCreateStatic + #define pvTimerGetTimerID MPU_pvTimerGetTimerID + #define vTimerSetTimerID MPU_vTimerSetTimerID + #define xTimerIsTimerActive MPU_xTimerIsTimerActive + #define xTimerGetTimerDaemonTaskHandle MPU_xTimerGetTimerDaemonTaskHandle + #define xTimerPendFunctionCall MPU_xTimerPendFunctionCall + #define pcTimerGetName MPU_pcTimerGetName + #define vTimerSetReloadMode MPU_vTimerSetReloadMode + #define xTimerGetPeriod MPU_xTimerGetPeriod + #define xTimerGetExpiryTime MPU_xTimerGetExpiryTime + #define xTimerGenericCommand MPU_xTimerGenericCommand + + /* Map standard event_group.h API functions to the MPU equivalents. */ + #define xEventGroupCreate MPU_xEventGroupCreate + #define xEventGroupCreateStatic MPU_xEventGroupCreateStatic + #define xEventGroupWaitBits MPU_xEventGroupWaitBits + #define xEventGroupClearBits MPU_xEventGroupClearBits + #define xEventGroupSetBits MPU_xEventGroupSetBits + #define xEventGroupSync MPU_xEventGroupSync + #define vEventGroupDelete MPU_vEventGroupDelete + + /* Map standard message/stream_buffer.h API functions to the MPU + equivalents. */ + #define xStreamBufferSend MPU_xStreamBufferSend + #define xStreamBufferReceive MPU_xStreamBufferReceive + #define xStreamBufferNextMessageLengthBytes MPU_xStreamBufferNextMessageLengthBytes + #define vStreamBufferDelete MPU_vStreamBufferDelete + #define xStreamBufferIsFull MPU_xStreamBufferIsFull + #define xStreamBufferIsEmpty MPU_xStreamBufferIsEmpty + #define xStreamBufferReset MPU_xStreamBufferReset + #define xStreamBufferSpacesAvailable MPU_xStreamBufferSpacesAvailable + #define xStreamBufferBytesAvailable MPU_xStreamBufferBytesAvailable + #define xStreamBufferSetTriggerLevel MPU_xStreamBufferSetTriggerLevel + #define xStreamBufferGenericCreate MPU_xStreamBufferGenericCreate + #define xStreamBufferGenericCreateStatic MPU_xStreamBufferGenericCreateStatic + + + /* Remove the privileged function macro, but keep the PRIVILEGED_DATA + macro so applications can place data in privileged access sections + (useful when using statically allocated objects). */ + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + #define FREERTOS_SYSTEM_CALL + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + #define FREERTOS_SYSTEM_CALL __attribute__((section( "freertos_system_calls"))) + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define FREERTOS_SYSTEM_CALL + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/port.c b/lib/FreeRTOS-SAMD51/src/port.c new file mode 100644 index 0000000..5496f42 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/port.c @@ -0,0 +1,805 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/*----------------------------------------------------------- + * + * Arduino Arm CMF4 port + * + * Implementation of functions defined in portable.h for the ARM CMF4 port. + * Arduino changes marked by "Arduino framework integration" comments + *----------------------------------------------------------*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +#ifndef __VFP_FP__ + #error This port can only be used when the project options are configured to enable hardware floating point support. +#endif + +#ifndef configSYSTICK_CLOCK_HZ + #define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ + /* Ensure the SysTick is clocked at the same frequency as the core. */ + #define portNVIC_SYSTICK_CLK_BIT ( 1UL << 2UL ) +#else + /* The way the SysTick is clocked is not modified in case it is not the same + as the core. */ + #define portNVIC_SYSTICK_CLK_BIT ( 0 ) +#endif + +/* Constants required to manipulate the core. Registers first... */ +#define portNVIC_SYSTICK_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000e010 ) ) +#define portNVIC_SYSTICK_LOAD_REG ( * ( ( volatile uint32_t * ) 0xe000e014 ) ) +#define portNVIC_SYSTICK_CURRENT_VALUE_REG ( * ( ( volatile uint32_t * ) 0xe000e018 ) ) +#define portNVIC_SYSPRI2_REG ( * ( ( volatile uint32_t * ) 0xe000ed20 ) ) +/* ...then bits in the registers. */ +#define portNVIC_SYSTICK_INT_BIT ( 1UL << 1UL ) +#define portNVIC_SYSTICK_ENABLE_BIT ( 1UL << 0UL ) +#define portNVIC_SYSTICK_COUNT_FLAG_BIT ( 1UL << 16UL ) +#define portNVIC_PENDSVCLEAR_BIT ( 1UL << 27UL ) +#define portNVIC_PEND_SYSTICK_CLEAR_BIT ( 1UL << 25UL ) + +/* Constants used to detect a Cortex-M7 r0p1 core, which should use the ARM_CM7 +r0p1 port. */ +#define portCPUID ( * ( ( volatile uint32_t * ) 0xE000ed00 ) ) +#define portCORTEX_M7_r0p1_ID ( 0x410FC271UL ) +#define portCORTEX_M7_r0p0_ID ( 0x410FC270UL ) + +#define portNVIC_PENDSV_PRI ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL ) +#define portNVIC_SYSTICK_PRI ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL ) + +/* Constants required to check the validity of an interrupt priority. */ +#define portFIRST_USER_INTERRUPT_NUMBER ( 16 ) +#define portNVIC_IP_REGISTERS_OFFSET_16 ( 0xE000E3F0 ) +#define portAIRCR_REG ( * ( ( volatile uint32_t * ) 0xE000ED0C ) ) +#define portMAX_8_BIT_VALUE ( ( uint8_t ) 0xff ) +#define portTOP_BIT_OF_BYTE ( ( uint8_t ) 0x80 ) +#define portMAX_PRIGROUP_BITS ( ( uint8_t ) 7 ) +#define portPRIORITY_GROUP_MASK ( 0x07UL << 8UL ) +#define portPRIGROUP_SHIFT ( 8UL ) + +/* Masks off all bits but the VECTACTIVE bits in the ICSR register. */ +#define portVECTACTIVE_MASK ( 0xFFUL ) + +/* Constants required to manipulate the VFP. */ +#define portFPCCR ( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating point context control register. */ +#define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL ) + +/* Constants required to set up the initial stack. */ +#define portINITIAL_XPSR ( 0x01000000 ) +#define portINITIAL_EXC_RETURN ( 0xfffffffd ) + +/* The systick is a 24-bit counter. */ +#define portMAX_24_BIT_NUMBER ( 0xffffffUL ) + +/* For strict compliance with the Cortex-M spec the task start address should +have bit-0 clear, as it is loaded into the PC on exit from an ISR. */ +#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL ) + +/* A fiddle factor to estimate the number of SysTick counts that would have +occurred while the SysTick counter is stopped during tickless idle +calculations. */ +#define portMISSED_COUNTS_FACTOR ( 45UL ) + +/* Let the user override the pre-loading of the initial LR with the address of +prvTaskExitError() in case it messes up unwinding of the stack in the +debugger. */ +#ifdef configTASK_RETURN_ADDRESS + #define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS +#else + #define portTASK_RETURN_ADDRESS prvTaskExitError +#endif + +/* + * Setup the timer to generate the tick interrupts. The implementation in this + * file is weak to allow application writers to change the timer used to + * generate the tick interrupt. + */ +void vPortSetupTimerInterrupt( void ); + +/* + * Exception handlers. + */ +void xPortPendSVHandler( void ) __attribute__ (( naked )); +void xPortSysTickHandler( void ); +void vPortSVCHandler( void ) __attribute__ (( naked )); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +static void prvPortStartFirstTask( void ) __attribute__ (( naked )); + +/* + * Function to enable the VFP. + */ +static void vPortEnableVFP( void ) __attribute__ (( naked )); + +/* + * Used to catch tasks that attempt to return from their implementing function. + */ +static void prvTaskExitError( void ); + +/*-----------------------------------------------------------*/ + +/* Each task maintains its own interrupt status in the critical nesting +variable. */ +static UBaseType_t uxCriticalNesting = 0xaaaaaaaa; + +/* + * The number of SysTick increments that make up one tick period. + */ +#if( configUSE_TICKLESS_IDLE == 1 ) + static uint32_t ulTimerCountsForOneTick = 0; +#endif /* configUSE_TICKLESS_IDLE */ + +/* + * The maximum number of tick periods that can be suppressed is limited by the + * 24 bit resolution of the SysTick timer. + */ +#if( configUSE_TICKLESS_IDLE == 1 ) + static uint32_t xMaximumPossibleSuppressedTicks = 0; +#endif /* configUSE_TICKLESS_IDLE */ + +/* + * Compensate for the CPU cycles that pass while the SysTick is stopped (low + * power functionality only. + */ +#if( configUSE_TICKLESS_IDLE == 1 ) + static uint32_t ulStoppedTimerCompensation = 0; +#endif /* configUSE_TICKLESS_IDLE */ + +/* + * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure + * FreeRTOS API functions are not called from interrupts that have been assigned + * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY. + */ +#if( configASSERT_DEFINED == 1 ) + static uint8_t ucMaxSysCallPriority = 0; + static uint32_t ulMaxPRIGROUPValue = 0; + static const volatile uint8_t * const pcInterruptPriorityRegisters = ( const volatile uint8_t * const ) portNVIC_IP_REGISTERS_OFFSET_16; +#endif /* configASSERT_DEFINED */ + +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters ) +{ + /* Simulate the stack frame as it would be created by a context switch + interrupt. */ + + /* Offset added to account for the way the MCU uses the stack on entry/exit + of interrupts, and to ensure alignment. */ + pxTopOfStack--; + + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */ + pxTopOfStack--; + *pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */ + + /* Save code space by skipping register initialisation. */ + pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ + *pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */ + + /* A save method is being used that requires each task to maintain its + own exec return value. */ + pxTopOfStack--; + *pxTopOfStack = portINITIAL_EXC_RETURN; + + pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +static void prvTaskExitError( void ) +{ +volatile uint32_t ulDummy = 0; + + /* A function that implements a task must not exit or attempt to return to + its caller as there is nothing to return to. If a task wants to exit it + should instead call vTaskDelete( NULL ). + + Artificially force an assert() to be triggered if configASSERT() is + defined, then stop here so application writers can catch the error. */ + configASSERT( uxCriticalNesting == ~0UL ); + portDISABLE_INTERRUPTS(); + while( ulDummy == 0 ) + { + /* This file calls prvTaskExitError() after the scheduler has been + started to remove a compiler warning about the function being defined + but never called. ulDummy is used purely to quieten other warnings + about code appearing after this function is called - making ulDummy + volatile makes the compiler think the function could return and + therefore not output an 'unreachable code' warning for code that appears + after it. */ + } +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler( void ) +{ + __asm volatile ( + " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ + " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ + " msr psp, r0 \n" /* Restore the task stack pointer. */ + " isb \n" + " mov r0, #0 \n" + " msr basepri, r0 \n" + " bx r14 \n" + " \n" + " .align 4 \n" + "pxCurrentTCBConst2: .word pxCurrentTCB \n" + ); +} +/*-----------------------------------------------------------*/ + +static void prvPortStartFirstTask( void ) +{ + /* Start the first task. This also clears the bit that indicates the FPU is + in use in case the FPU was used before the scheduler was started - which + would otherwise result in the unnecessary leaving of space in the SVC stack + for lazy saving of FPU registers. */ + __asm volatile( + " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" + " ldr r0, [r0] \n" + " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ + " mov r0, #0 \n" /* Clear the bit that indicates the FPU is in use, see comment above. */ + " msr control, r0 \n" + " cpsie i \n" /* Globally enable interrupts. */ + " cpsie f \n" + " dsb \n" + " isb \n" + " svc 0 \n" /* System call to start first task. */ + " nop \n" + ); +} +/*-----------------------------------------------------------*/ + +/* + * Arduino framework integration // <----------------------------------------------------- + */ +void (*rtosSysTick_Handler)(void); + +int sysTickHook(void) +{ + if (rtosSysTick_Handler) + rtosSysTick_Handler(); + return 0; // return zero to keep running the arduino default handler! +} + +/* + * See header file for description. + */ +BaseType_t xPortStartScheduler( void ) +{ + + /* Arduino framework integration */ //<---------------------------------------------------- + rtosSysTick_Handler = &xPortSysTickHandler; + + /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. + See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ + configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); + + /* This port can be used on all revisions of the Cortex-M7 core other than + the r0p1 parts. r0p1 parts should use the port from the + /source/portable/GCC/ARM_CM7/r0p1 directory. */ + configASSERT( portCPUID != portCORTEX_M7_r0p1_ID ); + configASSERT( portCPUID != portCORTEX_M7_r0p0_ID ); + + #if( configASSERT_DEFINED == 1 ) + { + volatile uint32_t ulOriginalPriority; + volatile uint8_t * const pucFirstUserPriorityRegister = ( volatile uint8_t * const ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER ); + volatile uint8_t ucMaxPriorityValue; + + /* Determine the maximum priority from which ISR safe FreeRTOS API + functions can be called. ISR safe functions are those that end in + "FromISR". FreeRTOS maintains separate thread and ISR API functions to + ensure interrupt entry is as fast and simple as possible. + + Save the interrupt priority value that is about to be clobbered. */ + ulOriginalPriority = *pucFirstUserPriorityRegister; + + /* Determine the number of priority bits available. First write to all + possible bits. */ + *pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE; + + /* Read the value back to see how many bits stuck. */ + ucMaxPriorityValue = *pucFirstUserPriorityRegister; + + /* Use the same mask on the maximum system call priority. */ + ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue; + + /* Calculate the maximum acceptable priority group value for the number + of bits read back. */ + ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS; + while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE ) + { + ulMaxPRIGROUPValue--; + ucMaxPriorityValue <<= ( uint8_t ) 0x01; + } + + #ifdef __NVIC_PRIO_BITS + { + /* Check the CMSIS configuration that defines the number of + priority bits matches the number of priority bits actually queried + from the hardware. */ + configASSERT( ( portMAX_PRIGROUP_BITS - ulMaxPRIGROUPValue ) == __NVIC_PRIO_BITS ); + } + #endif + + #ifdef configPRIO_BITS + { + /* Check the FreeRTOS configuration that defines the number of + priority bits matches the number of priority bits actually queried + from the hardware. */ + configASSERT( ( portMAX_PRIGROUP_BITS - ulMaxPRIGROUPValue ) == configPRIO_BITS ); + } + #endif + + /* Shift the priority group value back to its position within the AIRCR + register. */ + ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT; + ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK; + + /* Restore the clobbered interrupt priority register to its original + value. */ + *pucFirstUserPriorityRegister = ulOriginalPriority; + } + #endif /* conifgASSERT_DEFINED */ + + /* Make PendSV and SysTick the lowest priority interrupts. */ + portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI; + portNVIC_SYSPRI2_REG |= portNVIC_SYSTICK_PRI; + + /* Start the timer that generates the tick ISR. Interrupts are disabled + here already. */ + vPortSetupTimerInterrupt(); + + /* Initialise the critical nesting count ready for the first task. */ + uxCriticalNesting = 0; + + /* Ensure the VFP is enabled - it should be anyway. */ + vPortEnableVFP(); + + /* Lazy save always. */ + *( portFPCCR ) |= portASPEN_AND_LSPEN_BITS; + + /* Start the first task. */ + prvPortStartFirstTask(); + + /* Should never get here as the tasks will now be executing! Call the task + exit error function to prevent compiler warnings about a static function + not being called in the case that the application writer overrides this + functionality by defining configTASK_RETURN_ADDRESS. Call + vTaskSwitchContext() so link time optimisation does not remove the + symbol. */ + + + /* disabled for Arduino framework integration*/ // <----------------------------------------------------- Arduino + //vTaskSwitchContext(); + //prvTaskExitError(); + + + /* Should not get here! */ + return 0; +} + +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) +{ + /* Not implemented in ports where there is nothing to return to. + Artificially force an assert. */ + configASSERT( uxCriticalNesting == 1000UL ); +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) +{ + portDISABLE_INTERRUPTS(); + uxCriticalNesting++; + + /* This is not the interrupt safe version of the enter critical function so + assert() if it is being called from an interrupt context. Only API + functions that end in "FromISR" can be used in an interrupt. Only assert if + the critical nesting count is 1 to protect against recursive calls if the + assert function also uses a critical section. */ + if( uxCriticalNesting == 1 ) + { + configASSERT( ( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK ) == 0 ); + } +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) +{ + configASSERT( uxCriticalNesting ); + uxCriticalNesting--; + if( uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void xPortPendSVHandler( void ) +{ + /* This is a naked function. */ + + __asm volatile + ( + " mrs r0, psp \n" + " isb \n" + " \n" + " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ + " ldr r2, [r3] \n" + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */ + " it eq \n" + " vstmdbeq r0!, {s16-s31} \n" + " \n" + " stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */ + " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ + " \n" + " stmdb sp!, {r0, r3} \n" + " mov r0, %0 \n" + " msr basepri, r0 \n" + " dsb \n" + " isb \n" + " bl vTaskSwitchContext \n" + " mov r0, #0 \n" + " msr basepri, r0 \n" + " ldmia sp!, {r0, r3} \n" + " \n" + " ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldr r0, [r1] \n" + " \n" + " ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */ + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */ + " it eq \n" + " vldmiaeq r0!, {s16-s31} \n" + " \n" + " msr psp, r0 \n" + " isb \n" + " \n" + #ifdef WORKAROUND_PMU_CM001 /* XMC4000 specific errata workaround. */ + #if WORKAROUND_PMU_CM001 == 1 + " push { r14 } \n" + " pop { pc } \n" + #endif + #endif + " \n" + " bx r14 \n" + " \n" + " .align 4 \n" + "pxCurrentTCBConst: .word pxCurrentTCB \n" + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) + ); +} +/*-----------------------------------------------------------*/ + +void xPortSysTickHandler( void ) +{ + /* The SysTick runs at the lowest interrupt priority, so when this interrupt + executes all interrupts must be unmasked. There is therefore no need to + save and then restore the interrupt mask value as its value is already + known. */ + portDISABLE_INTERRUPTS(); + { + /* Increment the RTOS tick. */ + if( xTaskIncrementTick() != pdFALSE ) + { + /* A context switch is required. Context switching is performed in + the PendSV interrupt. Pend the PendSV interrupt. */ + portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT; + } + } + portENABLE_INTERRUPTS(); +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TICKLESS_IDLE == 1 ) + + __attribute__((weak)) void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime ) + { + uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements; + TickType_t xModifiableIdleTime; + + /* Make sure the SysTick reload value does not overflow the counter. */ + if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks ) + { + xExpectedIdleTime = xMaximumPossibleSuppressedTicks; + } + + /* Stop the SysTick momentarily. The time the SysTick is stopped for + is accounted for as best it can be, but using the tickless mode will + inevitably result in some tiny drift of the time maintained by the + kernel with respect to calendar time. */ + portNVIC_SYSTICK_CTRL_REG &= ~portNVIC_SYSTICK_ENABLE_BIT; + + /* Calculate the reload value required to wait xExpectedIdleTime + tick periods. -1 is used because this code will execute part way + through one of the tick periods. */ + ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) ); + if( ulReloadValue > ulStoppedTimerCompensation ) + { + ulReloadValue -= ulStoppedTimerCompensation; + } + + /* Enter a critical section but don't use the taskENTER_CRITICAL() + method as that will mask interrupts that should exit sleep mode. */ + __asm volatile( "cpsid i" ::: "memory" ); + __asm volatile( "dsb" ); + __asm volatile( "isb" ); + + /* If a context switch is pending or a task is waiting for the scheduler + to be unsuspended then abandon the low power entry. */ + if( eTaskConfirmSleepModeStatus() == eAbortSleep ) + { + /* Restart from whatever is left in the count register to complete + this tick period. */ + portNVIC_SYSTICK_LOAD_REG = portNVIC_SYSTICK_CURRENT_VALUE_REG; + + /* Restart SysTick. */ + portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT; + + /* Reset the reload register to the value required for normal tick + periods. */ + portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL; + + /* Re-enable interrupts - see comments above the cpsid instruction() + above. */ + __asm volatile( "cpsie i" ::: "memory" ); + } + else + { + /* Set the new reload value. */ + portNVIC_SYSTICK_LOAD_REG = ulReloadValue; + + /* Clear the SysTick count flag and set the count value back to + zero. */ + portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL; + + /* Restart SysTick. */ + portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT; + + /* Sleep until something happens. configPRE_SLEEP_PROCESSING() can + set its parameter to 0 to indicate that its implementation contains + its own wait for interrupt or wait for event instruction, and so wfi + should not be executed again. However, the original expected idle + time variable must remain unmodified, so a copy is taken. */ + xModifiableIdleTime = xExpectedIdleTime; + configPRE_SLEEP_PROCESSING( xModifiableIdleTime ); + if( xModifiableIdleTime > 0 ) + { + __asm volatile( "dsb" ::: "memory" ); + __asm volatile( "wfi" ); + __asm volatile( "isb" ); + } + configPOST_SLEEP_PROCESSING( xExpectedIdleTime ); + + /* Re-enable interrupts to allow the interrupt that brought the MCU + out of sleep mode to execute immediately. see comments above + __disable_interrupt() call above. */ + __asm volatile( "cpsie i" ::: "memory" ); + __asm volatile( "dsb" ); + __asm volatile( "isb" ); + + /* Disable interrupts again because the clock is about to be stopped + and interrupts that execute while the clock is stopped will increase + any slippage between the time maintained by the RTOS and calendar + time. */ + __asm volatile( "cpsid i" ::: "memory" ); + __asm volatile( "dsb" ); + __asm volatile( "isb" ); + + /* Disable the SysTick clock without reading the + portNVIC_SYSTICK_CTRL_REG register to ensure the + portNVIC_SYSTICK_COUNT_FLAG_BIT is not cleared if it is set. Again, + the time the SysTick is stopped for is accounted for as best it can + be, but using the tickless mode will inevitably result in some tiny + drift of the time maintained by the kernel with respect to calendar + time*/ + portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT ); + + /* Determine if the SysTick clock has already counted to zero and + been set back to the current reload value (the reload back being + correct for the entire expected idle time) or if the SysTick is yet + to count to zero (in which case an interrupt other than the SysTick + must have brought the system out of sleep mode). */ + if( ( portNVIC_SYSTICK_CTRL_REG & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 ) + { + uint32_t ulCalculatedLoadValue; + + /* The tick interrupt is already pending, and the SysTick count + reloaded with ulReloadValue. Reset the + portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick + period. */ + ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG ); + + /* Don't allow a tiny value, or values that have somehow + underflowed because the post sleep hook did something + that took too long. */ + if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) ) + { + ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ); + } + + portNVIC_SYSTICK_LOAD_REG = ulCalculatedLoadValue; + + /* As the pending tick will be processed as soon as this + function exits, the tick value maintained by the tick is stepped + forward by one less than the time spent waiting. */ + ulCompleteTickPeriods = xExpectedIdleTime - 1UL; + } + else + { + /* Something other than the tick interrupt ended the sleep. + Work out how long the sleep lasted rounded to complete tick + periods (not the ulReload value which accounted for part + ticks). */ + ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG; + + /* How many complete tick periods passed while the processor + was waiting? */ + ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick; + + /* The reload value is set to whatever fraction of a single tick + period remains. */ + portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1UL ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements; + } + + /* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG + again, then set portNVIC_SYSTICK_LOAD_REG back to its standard + value. */ + portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL; + portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT; + vTaskStepTick( ulCompleteTickPeriods ); + portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL; + + /* Exit with interrpts enabled. */ + __asm volatile( "cpsie i" ::: "memory" ); + } + } + +#endif /* #if configUSE_TICKLESS_IDLE */ +/*-----------------------------------------------------------*/ + +/* + * Setup the systick timer to generate the tick interrupts at the required + * frequency. + */ +__attribute__(( weak )) void vPortSetupTimerInterrupt( void ) +{ + /* Calculate the constants required to configure the tick interrupt. */ + #if( configUSE_TICKLESS_IDLE == 1 ) + { + ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ); + xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick; + ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ ); + } + #endif /* configUSE_TICKLESS_IDLE */ + + /* Stop and clear the SysTick. */ + portNVIC_SYSTICK_CTRL_REG = 0UL; + portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL; + + /* Configure SysTick to interrupt at the requested rate. */ + portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT ); +} +/*-----------------------------------------------------------*/ + +/* This is a naked function. */ +static void vPortEnableVFP( void ) +{ + __asm volatile + ( + " ldr.w r0, =0xE000ED88 \n" /* The FPU enable bits are in the CPACR. */ + " ldr r1, [r0] \n" + " \n" + " orr r1, r1, #( 0xf << 20 ) \n" /* Enable CP10 and CP11 coprocessors, then save back. */ + " str r1, [r0] \n" + " bx r14 " + ); +} +/*-----------------------------------------------------------*/ + +#if( configASSERT_DEFINED == 1 ) + + void vPortValidateInterruptPriority( void ) + { + uint32_t ulCurrentInterrupt; + uint8_t ucCurrentPriority; + + /* Obtain the number of the currently executing interrupt. */ + __asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" ); + + /* Is the interrupt number a user defined interrupt? */ + if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER ) + { + /* Look up the interrupt's priority. */ + ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ]; + + /* The following assertion will fail if a service routine (ISR) for + an interrupt that has been assigned a priority above + configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API + function. ISR safe FreeRTOS API functions must *only* be called + from interrupts that have been assigned a priority at or below + configMAX_SYSCALL_INTERRUPT_PRIORITY. + + Numerically low interrupt priority numbers represent logically high + interrupt priorities, therefore the priority of the interrupt must + be set to a value equal to or numerically *higher* than + configMAX_SYSCALL_INTERRUPT_PRIORITY. + + Interrupts that use the FreeRTOS API must not be left at their + default priority of zero as that is the highest possible priority, + which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY, + and therefore also guaranteed to be invalid. + + FreeRTOS maintains separate thread and ISR API functions to ensure + interrupt entry is as fast and simple as possible. + + The following links provide detailed information: + http://www.freertos.org/RTOS-Cortex-M3-M4.html + http://www.freertos.org/FAQHelp.html */ + + // "Arduino framework integration" + // use this to help debug the interrupts priority thats causing the issue in rtos + configPrintASSERT( ucCurrentPriority >= ucMaxSysCallPriority, ucCurrentPriority, ">=", ucMaxSysCallPriority); + //configASSERT( ucCurrentPriority >= ucMaxSysCallPriority ); + } + + /* Priority grouping: The interrupt controller (NVIC) allows the bits + that define each interrupt's priority to be split between bits that + define the interrupt's pre-emption priority bits and bits that define + the interrupt's sub-priority. For simplicity all bits must be defined + to be pre-emption priority bits. The following assertion will fail if + this is not the case (if some bits represent a sub-priority). + + If the application only uses CMSIS libraries for interrupt + configuration then the correct setting can be achieved on all Cortex-M + devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the + scheduler. Note however that some vendor specific peripheral libraries + assume a non-zero priority group setting, in which cases using a value + of zero will result in unpredictable behaviour. */ + configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue ); + } + +#endif /* configASSERT_DEFINED */ + + + diff --git a/lib/FreeRTOS-SAMD51/src/portable.h b/lib/FreeRTOS-SAMD51/src/portable.h new file mode 100644 index 0000000..03279c6 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/portable.h @@ -0,0 +1,183 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Each FreeRTOS port has a unique portmacro.h header file. Originally a +pre-processor definition was used to ensure the pre-processor found the correct +portmacro.h file for the port being used. That scheme was deprecated in favour +of setting the compiler's include path such that it found the correct +portmacro.h file - removing the need for the constant and allowing the +portmacro.h file to be located anywhere in relation to the port being used. +Purely for reasons of backward compatibility the old method is still valid, but +to make it clear that new projects should not use it, support for the port +specific constants has been moved into the deprecated_definitions.h header +file. */ +#include "deprecated_definitions.h" + +/* If portENTER_CRITICAL is not defined then including deprecated_definitions.h +did not result in a portmacro.h header file being included - and it should be +included here. In this case the path to the correct portmacro.h header file +must be set in the compiler's include path. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 32 + #define portBYTE_ALIGNMENT_MASK ( 0x001f ) +#endif + +#if portBYTE_ALIGNMENT == 16 + #define portBYTE_ALIGNMENT_MASK ( 0x000f ) +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifndef portHAS_STACK_OVERFLOW_CHECKING + #define portHAS_STACK_OVERFLOW_CHECKING 0 +#endif + +#ifndef portARCH_NAME + #define portARCH_NAME NULL +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION; + #else + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION; + #endif +#else + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, StackType_t *pxEndOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION; + #else + StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION; + #endif +#endif + +/* Used by heap_5.c. */ +typedef struct HeapRegion +{ + uint8_t *pucStartAddress; + size_t xSizeInBytes; +} HeapRegion_t; + +/* + * Used to define multiple heap regions for use by heap_5.c. This function + * must be called before any calls to pvPortMalloc() - not creating a task, + * queue, semaphore, mutex, software timer, event group, etc. will result in + * pvPortMalloc being called. + * + * pxHeapRegions passes in an array of HeapRegion_t structures - each of which + * defines a region of memory that can be used as the heap. The array is + * terminated by a HeapRegions_t structure that has a size of 0. The region + * with the lowest start address must appear first in the array. + */ +void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions ) PRIVILEGED_FUNCTION; + + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void *pvPortRealloc(void* ptr, size_t _size) PRIVILEGED_FUNCTION; +void *pvPortCalloc(size_t nmemb, size_t _size) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; +size_t xPortGetMinimumEverFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +BaseType_t xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, StackType_t *pxBottomOfStack, uint32_t ulStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/portmacro.h b/lib/FreeRTOS-SAMD51/src/portmacro.h new file mode 100644 index 0000000..e0c3de7 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/portmacro.h @@ -0,0 +1,244 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE uint32_t +#define portBASE_TYPE long + +typedef portSTACK_TYPE StackType_t; +typedef long BaseType_t; +typedef unsigned long UBaseType_t; + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef uint16_t TickType_t; + #define portMAX_DELAY ( TickType_t ) 0xffff +#else + typedef uint32_t TickType_t; + #define portMAX_DELAY ( TickType_t ) 0xffffffffUL + + /* 32-bit tick type on a 32-bit architecture, so reads of the tick count do + not need to be guarded with a critical section. */ + #define portTICK_TYPE_IS_ATOMIC 1 +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ ) +#define portTICK_PERIOD_US ( ( TickType_t ) 1000000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 8 +/*-----------------------------------------------------------*/ + +/* Scheduler utilities. */ +#define portYIELD() \ +{ \ + /* Set a PendSV to request a context switch. */ \ + portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT; \ + \ + /* Barriers are normally not required but do ensure the code is completely \ + within the specified behaviour for the architecture. */ \ + __asm volatile( "dsb" ::: "memory" ); \ + __asm volatile( "isb" ); \ +} + +#define portNVIC_INT_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000ed04 ) ) +#define portNVIC_PENDSVSET_BIT ( 1UL << 28UL ) +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired != pdFALSE ) portYIELD() +#define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x ) +/*-----------------------------------------------------------*/ + +/* Critical section management. */ +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); +#define portSET_INTERRUPT_MASK_FROM_ISR() ulPortRaiseBASEPRI() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortSetBASEPRI(x) +#define portDISABLE_INTERRUPTS() vPortRaiseBASEPRI() +#define portENABLE_INTERRUPTS() vPortSetBASEPRI(0) +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() + +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. These are +not necessary for to use this port. They are defined so the common demo files +(which build with all the ports) will build. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) +/*-----------------------------------------------------------*/ + +/* Tickless idle/low power functionality. */ +#ifndef portSUPPRESS_TICKS_AND_SLEEP + extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime ); + #define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime ) +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specific optimisations. */ +#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION + #define configUSE_PORT_OPTIMISED_TASK_SELECTION 1 +#endif + +#if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1 + + /* Generic helper function. */ + __attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros( uint32_t ulBitmap ) + { + uint8_t ucReturn; + + __asm volatile ( "clz %0, %1" : "=r" ( ucReturn ) : "r" ( ulBitmap ) : "memory" ); + return ucReturn; + } + + /* Check the configuration. */ + #if( configMAX_PRIORITIES > 32 ) + #error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice. + #endif + + /* Store/clear the ready priorities in a bit map. */ + #define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) ) + #define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) ) + + /*-----------------------------------------------------------*/ + + #define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31UL - ( uint32_t ) ucPortCountLeadingZeros( ( uxReadyPriorities ) ) ) + +#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ + +/*-----------------------------------------------------------*/ + +#ifdef configASSERT + void vPortValidateInterruptPriority( void ); + #define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority() +#endif + +/* portNOP() is not required by this port. */ +#define portNOP() + +#define portINLINE __inline + +#ifndef portFORCE_INLINE + #define portFORCE_INLINE inline __attribute__(( always_inline)) +#endif + +portFORCE_INLINE static BaseType_t xPortIsInsideInterrupt( void ) +{ +uint32_t ulCurrentInterrupt; +BaseType_t xReturn; + + /* Obtain the number of the currently executing interrupt. */ + __asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" ); + + if( ulCurrentInterrupt == 0 ) + { + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + + return xReturn; +} + +/*-----------------------------------------------------------*/ + +portFORCE_INLINE static void vPortRaiseBASEPRI( void ) +{ +uint32_t ulNewBASEPRI; + + __asm volatile + ( + " mov %0, %1 \n" \ + " msr basepri, %0 \n" \ + " isb \n" \ + " dsb \n" \ + :"=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory" + ); +} + +/*-----------------------------------------------------------*/ + +portFORCE_INLINE static uint32_t ulPortRaiseBASEPRI( void ) +{ +uint32_t ulOriginalBASEPRI, ulNewBASEPRI; + + __asm volatile + ( + " mrs %0, basepri \n" \ + " mov %1, %2 \n" \ + " msr basepri, %1 \n" \ + " isb \n" \ + " dsb \n" \ + :"=r" (ulOriginalBASEPRI), "=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory" + ); + + /* This return will not be reached but is necessary to prevent compiler + warnings. */ + return ulOriginalBASEPRI; +} +/*-----------------------------------------------------------*/ + +portFORCE_INLINE static void vPortSetBASEPRI( uint32_t ulNewMaskValue ) +{ + __asm volatile + ( + " msr basepri, %0 " :: "r" ( ulNewMaskValue ) : "memory" + ); +} +/*-----------------------------------------------------------*/ + +#define portMEMORY_BARRIER() __asm volatile( "" ::: "memory" ) + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/projdefs.h b/lib/FreeRTOS-SAMD51/src/projdefs.h new file mode 100644 index 0000000..e045861 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/projdefs.h @@ -0,0 +1,124 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +/* + * Defines the prototype to which task functions must conform. Defined in this + * file to ensure the type is known before portable.h is included. + */ +typedef void (*TaskFunction_t)( void * ); + +/* Converts a time in milliseconds to a time in ticks. This macro can be +overridden by a macro of the same name defined in FreeRTOSConfig.h in case the +definition here is not suitable for your application. */ +#ifndef pdMS_TO_TICKS + #define pdMS_TO_TICKS( xTimeInMs ) ( ( TickType_t ) ( ( ( TickType_t ) ( xTimeInMs ) * ( TickType_t ) configTICK_RATE_HZ ) / ( TickType_t ) 1000 ) ) +#endif + +#define pdFALSE ( ( BaseType_t ) 0 ) +#define pdTRUE ( ( BaseType_t ) 1 ) + +#define pdPASS ( pdTRUE ) +#define pdFAIL ( pdFALSE ) +#define errQUEUE_EMPTY ( ( BaseType_t ) 0 ) +#define errQUEUE_FULL ( ( BaseType_t ) 0 ) + +/* FreeRTOS error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +/* Macros used for basic data corruption checks. */ +#ifndef configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES + #define configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 0 +#endif + +#if( configUSE_16_BIT_TICKS == 1 ) + #define pdINTEGRITY_CHECK_VALUE 0x5a5a +#else + #define pdINTEGRITY_CHECK_VALUE 0x5a5a5a5aUL +#endif + +/* The following errno values are used by FreeRTOS+ components, not FreeRTOS +itself. */ +#define pdFREERTOS_ERRNO_NONE 0 /* No errors */ +#define pdFREERTOS_ERRNO_ENOENT 2 /* No such file or directory */ +#define pdFREERTOS_ERRNO_EINTR 4 /* Interrupted system call */ +#define pdFREERTOS_ERRNO_EIO 5 /* I/O error */ +#define pdFREERTOS_ERRNO_ENXIO 6 /* No such device or address */ +#define pdFREERTOS_ERRNO_EBADF 9 /* Bad file number */ +#define pdFREERTOS_ERRNO_EAGAIN 11 /* No more processes */ +#define pdFREERTOS_ERRNO_EWOULDBLOCK 11 /* Operation would block */ +#define pdFREERTOS_ERRNO_ENOMEM 12 /* Not enough memory */ +#define pdFREERTOS_ERRNO_EACCES 13 /* Permission denied */ +#define pdFREERTOS_ERRNO_EFAULT 14 /* Bad address */ +#define pdFREERTOS_ERRNO_EBUSY 16 /* Mount device busy */ +#define pdFREERTOS_ERRNO_EEXIST 17 /* File exists */ +#define pdFREERTOS_ERRNO_EXDEV 18 /* Cross-device link */ +#define pdFREERTOS_ERRNO_ENODEV 19 /* No such device */ +#define pdFREERTOS_ERRNO_ENOTDIR 20 /* Not a directory */ +#define pdFREERTOS_ERRNO_EISDIR 21 /* Is a directory */ +#define pdFREERTOS_ERRNO_EINVAL 22 /* Invalid argument */ +#define pdFREERTOS_ERRNO_ENOSPC 28 /* No space left on device */ +#define pdFREERTOS_ERRNO_ESPIPE 29 /* Illegal seek */ +#define pdFREERTOS_ERRNO_EROFS 30 /* Read only file system */ +#define pdFREERTOS_ERRNO_EUNATCH 42 /* Protocol driver not attached */ +#define pdFREERTOS_ERRNO_EBADE 50 /* Invalid exchange */ +#define pdFREERTOS_ERRNO_EFTYPE 79 /* Inappropriate file type or format */ +#define pdFREERTOS_ERRNO_ENMFILE 89 /* No more files */ +#define pdFREERTOS_ERRNO_ENOTEMPTY 90 /* Directory not empty */ +#define pdFREERTOS_ERRNO_ENAMETOOLONG 91 /* File or path name too long */ +#define pdFREERTOS_ERRNO_EOPNOTSUPP 95 /* Operation not supported on transport endpoint */ +#define pdFREERTOS_ERRNO_ENOBUFS 105 /* No buffer space available */ +#define pdFREERTOS_ERRNO_ENOPROTOOPT 109 /* Protocol not available */ +#define pdFREERTOS_ERRNO_EADDRINUSE 112 /* Address already in use */ +#define pdFREERTOS_ERRNO_ETIMEDOUT 116 /* Connection timed out */ +#define pdFREERTOS_ERRNO_EINPROGRESS 119 /* Connection already in progress */ +#define pdFREERTOS_ERRNO_EALREADY 120 /* Socket already connected */ +#define pdFREERTOS_ERRNO_EADDRNOTAVAIL 125 /* Address not available */ +#define pdFREERTOS_ERRNO_EISCONN 127 /* Socket is already connected */ +#define pdFREERTOS_ERRNO_ENOTCONN 128 /* Socket is not connected */ +#define pdFREERTOS_ERRNO_ENOMEDIUM 135 /* No medium inserted */ +#define pdFREERTOS_ERRNO_EILSEQ 138 /* An invalid UTF-16 sequence was encountered. */ +#define pdFREERTOS_ERRNO_ECANCELED 140 /* Operation canceled. */ + +/* The following endian values are used by FreeRTOS+ components, not FreeRTOS +itself. */ +#define pdFREERTOS_LITTLE_ENDIAN 0 +#define pdFREERTOS_BIG_ENDIAN 1 + +/* Re-defining endian values for generic naming. */ +#define pdLITTLE_ENDIAN pdFREERTOS_LITTLE_ENDIAN +#define pdBIG_ENDIAN pdFREERTOS_BIG_ENDIAN + + +#endif /* PROJDEFS_H */ + + + diff --git a/lib/FreeRTOS-SAMD51/src/queue.c b/lib/FreeRTOS-SAMD51/src/queue.c new file mode 100644 index 0000000..d882bf6 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/queue.c @@ -0,0 +1,2941 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( int8_t ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( int8_t ) 0 ) + +/* When the Queue_t structure is used to represent a base queue its pcHead and +pcTail members are used as pointers into the queue storage area. When the +Queue_t structure is used to represent a mutex pcHead and pcTail pointers are +not necessary, and the pcHead pointer is set to NULL to indicate that the +structure instead holds a pointer to the mutex holder (if any). Map alternative +names to the pcHead and structure member to ensure the readability of the code +is maintained. The QueuePointers_t and SemaphoreData_t types are used to form +a union as their usage is mutually exclusive dependent on what the queue is +being used for. */ +#define uxQueueType pcHead +#define queueQUEUE_IS_MUTEX NULL + +typedef struct QueuePointers +{ + int8_t *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + int8_t *pcReadFrom; /*< Points to the last place that a queued item was read from when the structure is used as a queue. */ +} QueuePointers_t; + +typedef struct SemaphoreData +{ + TaskHandle_t xMutexHolder; /*< The handle of the task that holds the mutex. */ + UBaseType_t uxRecursiveCallCount;/*< Maintains a count of the number of times a recursive mutex has been recursively 'taken' when the structure is used as a mutex. */ +} SemaphoreData_t; + +/* Semaphores do not actually store or copy data, so have an item size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( UBaseType_t ) 0 ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( TickType_t ) 0U ) + +#if( configUSE_PREEMPTION == 0 ) + /* If the cooperative scheduler is being used then a yield should not be + performed just because a higher priority task has been woken. */ + #define queueYIELD_IF_USING_PREEMPTION() +#else + #define queueYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API() +#endif + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. See the following link for the + * rationale: https://www.freertos.org/Embedded-RTOS-Queues.html + */ +typedef struct QueueDefinition /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + int8_t *pcHead; /*< Points to the beginning of the queue storage area. */ + int8_t *pcWriteTo; /*< Points to the free next place in the storage area. */ + + union + { + QueuePointers_t xQueue; /*< Data required exclusively when this structure is used as a queue. */ + SemaphoreData_t xSemaphore; /*< Data required exclusively when this structure is used as a semaphore. */ + } u; + + List_t xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + List_t xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile UBaseType_t uxMessagesWaiting;/*< The number of items currently in the queue. */ + UBaseType_t uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + UBaseType_t uxItemSize; /*< The size of each items that the queue will hold. */ + + volatile int8_t cRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile int8_t cTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + + #if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the memory used by the queue was statically allocated to ensure no attempt is made to free the memory. */ + #endif + + #if ( configUSE_QUEUE_SETS == 1 ) + struct QueueDefinition *pxQueueSetContainer; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxQueueNumber; + uint8_t ucQueueType; + #endif + +} xQUEUE; + +/* The old xQUEUE name is maintained above then typedefed to the new Queue_t +name below to enable the use of older kernel aware debuggers. */ +typedef xQUEUE Queue_t; + +/*-----------------------------------------------------------*/ + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + const char *pcQueueName; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + QueueHandle_t xHandle; + } xQueueRegistryItem; + + /* The old xQueueRegistryItem name is maintained above then typedefed to the + new xQueueRegistryItem name below to enable the use of older kernel aware + debuggers. */ + typedef xQueueRegistryItem QueueRegistryItem_t; + + /* The queue registry is simply an array of QueueRegistryItem_t structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + PRIVILEGED_DATA QueueRegistryItem_t xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + +#endif /* configQUEUE_REGISTRY_SIZE */ + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( Queue_t * const pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static BaseType_t prvIsQueueFull( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION; + +#if ( configUSE_QUEUE_SETS == 1 ) + /* + * Checks to see if a queue is a member of a queue set, and if so, notifies + * the queue set that the queue contains data. + */ + static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION; +#endif + +/* + * Called after a Queue_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewQueue( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, const uint8_t ucQueueType, Queue_t *pxNewQueue ) PRIVILEGED_FUNCTION; + +/* + * Mutexes are a special type of queue. When a mutex is created, first the + * queue is created, then prvInitialiseMutex() is called to configure the queue + * as a mutex. + */ +#if( configUSE_MUTEXES == 1 ) + static void prvInitialiseMutex( Queue_t *pxNewQueue ) PRIVILEGED_FUNCTION; +#endif + +#if( configUSE_MUTEXES == 1 ) + /* + * If a task waiting for a mutex causes the mutex holder to inherit a + * priority, but the waiting task times out, then the holder should + * disinherit the priority - but only down to the highest priority of any + * other tasks that are waiting for the same mutex. This function returns + * that priority. + */ + static UBaseType_t prvGetDisinheritPriorityAfterTimeout( const Queue_t * const pxQueue ) PRIVILEGED_FUNCTION; +#endif +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->cRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->cRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->cTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->cTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) +{ +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + pxQueue->u.xQueue.pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + pxQueue->uxMessagesWaiting = ( UBaseType_t ) 0U; + pxQueue->pcWriteTo = pxQueue->pcHead; + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - 1U ) * pxQueue->uxItemSize ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + pxQueue->cRxLock = queueUNLOCKED; + pxQueue->cTxLock = queueUNLOCKED; + + if( xNewQueue == pdFALSE ) + { + /* If there are tasks blocked waiting to read from the queue, then + the tasks will remain blocked as after this function exits the queue + will still be empty. If there are tasks blocked waiting to write to + the queue, then one should be unblocked as after this function exits + it will be possible to write to it. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Ensure the event queues start in the correct state. */ + vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); + } + } + taskEXIT_CRITICAL(); + + /* A value is returned for calling semantic consistency with previous + versions. */ + return pdPASS; +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + QueueHandle_t xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) + { + Queue_t *pxNewQueue; + + configASSERT( uxQueueLength > ( UBaseType_t ) 0 ); + + /* The StaticQueue_t structure and the queue storage area must be + supplied. */ + configASSERT( pxStaticQueue != NULL ); + + /* A queue storage area should be provided if the item size is not 0, and + should not be provided if the item size is 0. */ + configASSERT( !( ( pucQueueStorage != NULL ) && ( uxItemSize == 0 ) ) ); + configASSERT( !( ( pucQueueStorage == NULL ) && ( uxItemSize != 0 ) ) ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticQueue_t or StaticSemaphore_t equals the size of + the real queue and semaphore structures. */ + volatile size_t xSize = sizeof( StaticQueue_t ); + configASSERT( xSize == sizeof( Queue_t ) ); + ( void ) xSize; /* Keeps lint quiet when configASSERT() is not defined. */ + } + #endif /* configASSERT_DEFINED */ + + /* The address of a statically allocated queue was passed in, use it. + The address of a statically allocated storage area was also passed in + but is already set. */ + pxNewQueue = ( Queue_t * ) pxStaticQueue; /*lint !e740 !e9087 Unusual cast is ok as the structures are designed to have the same alignment, and the size is checked by an assert. */ + + if( pxNewQueue != NULL ) + { + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Queues can be allocated wither statically or dynamically, so + note this queue was allocated statically in case the queue is + later deleted. */ + pxNewQueue->ucStaticallyAllocated = pdTRUE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + + prvInitialiseNewQueue( uxQueueLength, uxItemSize, pucQueueStorage, ucQueueType, pxNewQueue ); + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + mtCOVERAGE_TEST_MARKER(); + } + + return pxNewQueue; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) + { + Queue_t *pxNewQueue; + size_t xQueueSizeInBytes; + uint8_t *pucQueueStorage; + + configASSERT( uxQueueLength > ( UBaseType_t ) 0 ); + + if( uxItemSize == ( UBaseType_t ) 0 ) + { + /* There is not going to be a queue storage area. */ + xQueueSizeInBytes = ( size_t ) 0; + } + else + { + /* Allocate enough space to hold the maximum number of items that + can be in the queue at any time. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + + /* Allocate the queue and storage area. Justification for MISRA + deviation as follows: pvPortMalloc() always ensures returned memory + blocks are aligned per the requirements of the MCU stack. In this case + pvPortMalloc() must return a pointer that is guaranteed to meet the + alignment requirements of the Queue_t structure - which in this case + is an int8_t *. Therefore, whenever the stack alignment requirements + are greater than or equal to the pointer to char requirements the cast + is safe. In other cases alignment requirements are not strict (one or + two bytes). */ + pxNewQueue = ( Queue_t * ) pvPortMalloc( sizeof( Queue_t ) + xQueueSizeInBytes ); /*lint !e9087 !e9079 see comment above. */ + + if( pxNewQueue != NULL ) + { + /* Jump past the queue structure to find the location of the queue + storage area. */ + pucQueueStorage = ( uint8_t * ) pxNewQueue; + pucQueueStorage += sizeof( Queue_t ); /*lint !e9016 Pointer arithmetic allowed on char types, especially when it assists conveying intent. */ + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* Queues can be created either statically or dynamically, so + note this task was created dynamically in case it is later + deleted. */ + pxNewQueue->ucStaticallyAllocated = pdFALSE; + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + prvInitialiseNewQueue( uxQueueLength, uxItemSize, pucQueueStorage, ucQueueType, pxNewQueue ); + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + mtCOVERAGE_TEST_MARKER(); + } + + return pxNewQueue; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewQueue( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, const uint8_t ucQueueType, Queue_t *pxNewQueue ) +{ + /* Remove compiler warnings about unused parameters should + configUSE_TRACE_FACILITY not be set to 1. */ + ( void ) ucQueueType; + + if( uxItemSize == ( UBaseType_t ) 0 ) + { + /* No RAM was allocated for the queue storage area, but PC head cannot + be set to NULL because NULL is used as a key to say the queue is used as + a mutex. Therefore just set pcHead to point to the queue as a benign + value that is known to be within the memory map. */ + pxNewQueue->pcHead = ( int8_t * ) pxNewQueue; + } + else + { + /* Set the head to the start of the queue storage area. */ + pxNewQueue->pcHead = ( int8_t * ) pucQueueStorage; + } + + /* Initialise the queue members as described where the queue type is + defined. */ + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + ( void ) xQueueGenericReset( pxNewQueue, pdTRUE ); + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif /* configUSE_TRACE_FACILITY */ + + #if( configUSE_QUEUE_SETS == 1 ) + { + pxNewQueue->pxQueueSetContainer = NULL; + } + #endif /* configUSE_QUEUE_SETS */ + + traceQUEUE_CREATE( pxNewQueue ); +} +/*-----------------------------------------------------------*/ + +#if( configUSE_MUTEXES == 1 ) + + static void prvInitialiseMutex( Queue_t *pxNewQueue ) + { + if( pxNewQueue != NULL ) + { + /* The queue create function will set all the queue structure members + correctly for a generic queue, but this function is creating a + mutex. Overwrite those members that need to be set differently - + in particular the information required for priority inheritance. */ + pxNewQueue->u.xSemaphore.xMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* In case this is a recursive mutex. */ + pxNewQueue->u.xSemaphore.uxRecursiveCallCount = 0; + + traceCREATE_MUTEX( pxNewQueue ); + + /* Start with the semaphore in the expected state. */ + ( void ) xQueueGenericSend( pxNewQueue, NULL, ( TickType_t ) 0U, queueSEND_TO_BACK ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType ) + { + QueueHandle_t xNewQueue; + const UBaseType_t uxMutexLength = ( UBaseType_t ) 1, uxMutexSize = ( UBaseType_t ) 0; + + xNewQueue = xQueueGenericCreate( uxMutexLength, uxMutexSize, ucQueueType ); + prvInitialiseMutex( ( Queue_t * ) xNewQueue ); + + return xNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_MUTEXES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) + { + QueueHandle_t xNewQueue; + const UBaseType_t uxMutexLength = ( UBaseType_t ) 1, uxMutexSize = ( UBaseType_t ) 0; + + /* Prevent compiler warnings about unused parameters if + configUSE_TRACE_FACILITY does not equal 1. */ + ( void ) ucQueueType; + + xNewQueue = xQueueGenericCreateStatic( uxMutexLength, uxMutexSize, NULL, pxStaticQueue, ucQueueType ); + prvInitialiseMutex( ( Queue_t * ) xNewQueue ); + + return xNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) ) + + TaskHandle_t xQueueGetMutexHolder( QueueHandle_t xSemaphore ) + { + TaskHandle_t pxReturn; + Queue_t * const pxSemaphore = ( Queue_t * ) xSemaphore; + + /* This function is called by xSemaphoreGetMutexHolder(), and should not + be called directly. Note: This is a good way of determining if the + calling task is the mutex holder, but not a good way of determining the + identity of the mutex holder, as the holder may change between the + following critical section exiting and the function returning. */ + taskENTER_CRITICAL(); + { + if( pxSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = pxSemaphore->u.xSemaphore.xMutexHolder; + } + else + { + pxReturn = NULL; + } + } + taskEXIT_CRITICAL(); + + return pxReturn; + } /*lint !e818 xSemaphore cannot be a pointer to const because it is a typedef. */ + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) ) + + TaskHandle_t xQueueGetMutexHolderFromISR( QueueHandle_t xSemaphore ) + { + TaskHandle_t pxReturn; + + configASSERT( xSemaphore ); + + /* Mutexes cannot be used in interrupt service routines, so the mutex + holder should not change in an ISR, and therefore a critical section is + not required here. */ + if( ( ( Queue_t * ) xSemaphore )->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = ( ( Queue_t * ) xSemaphore )->u.xSemaphore.xMutexHolder; + } + else + { + pxReturn = NULL; + } + + return pxReturn; + } /*lint !e818 xSemaphore cannot be a pointer to const because it is a typedef. */ + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + BaseType_t xQueueGiveMutexRecursive( QueueHandle_t xMutex ) + { + BaseType_t xReturn; + Queue_t * const pxMutex = ( Queue_t * ) xMutex; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then xMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->u.xSemaphore.xMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if xMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )--; + + /* Has the recursive call count unwound to 0? */ + if( pxMutex->u.xSemaphore.uxRecursiveCallCount == ( UBaseType_t ) 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + ( void ) xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = pdPASS; + } + else + { + /* The mutex cannot be given because the calling task is not the + holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxMutex = ( Queue_t * ) xMutex; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->u.xSemaphore.xMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueSemaphoreTake( pxMutex, xTicksToWait ); + + /* pdPASS will only be returned if the mutex was successfully + obtained. The calling task may have entered the Blocked state + before reaching here. */ + if( xReturn != pdFAIL ) + { + ( pxMutex->u.xSemaphore.uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) + { + QueueHandle_t xHandle; + + configASSERT( uxMaxCount != 0 ); + configASSERT( uxInitialCount <= uxMaxCount ); + + xHandle = xQueueGenericCreateStatic( uxMaxCount, queueSEMAPHORE_QUEUE_ITEM_LENGTH, NULL, pxStaticQueue, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( xHandle != NULL ) + { + ( ( Queue_t * ) xHandle )->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return xHandle; + } + +#endif /* ( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) + { + QueueHandle_t xHandle; + + configASSERT( uxMaxCount != 0 ); + configASSERT( uxInitialCount <= uxMaxCount ); + + xHandle = xQueueGenericCreate( uxMaxCount, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( xHandle != NULL ) + { + ( ( Queue_t * ) xHandle )->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return xHandle; + } + +#endif /* ( ( configUSE_COUNTING_SEMAPHORES == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) +{ +BaseType_t xEntryTimeSet = pdFALSE, xYieldRequired; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) ); + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? The running task must be the + highest priority task wanting to access the queue. If the head item + in the queue is to be overwritten then it does not matter if the + queue is full. */ + if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) ) + { + traceQUEUE_SEND( pxQueue ); + + #if ( configUSE_QUEUE_SETS == 1 ) + { + UBaseType_t uxPreviousMessagesWaiting = pxQueue->uxMessagesWaiting; + + xYieldRequired = prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( ( xCopyPosition == queueOVERWRITE ) && ( uxPreviousMessagesWaiting != ( UBaseType_t ) 0 ) ) + { + /* Do not notify the queue set as an existing item + was overwritten in the queue so the number of items + in the queue has not changed. */ + mtCOVERAGE_TEST_MARKER(); + } + else if( prvNotifyQueueSetContainer( pxQueue, xCopyPosition ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting + to the queue set caused a higher priority task to + unblock. A context switch is required. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to + do this from within the critical section - the + kernel takes care of that. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xYieldRequired != pdFALSE ) + { + /* This path is a special case that will only get + executed if the task was holding multiple mutexes + and the mutexes were given back in an order that is + different to that in which they were taken. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + xYieldRequired = prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else if( xYieldRequired != pdFALSE ) + { + /* This path is a special case that will only get + executed if the task was holding multiple mutexes and + the mutexes were given back in an order that is + different to that in which they were taken. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_QUEUE_SETS */ + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + /* Similar to xQueueGenericSend, except without blocking if there is no room + in the queue. Also don't directly wake a task that was blocked on a queue + read, instead return a flag to say whether a context switch is required or + not (i.e. has a task with a higher priority than us been woken by this + post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) ) + { + const int8_t cTxLock = pxQueue->cTxLock; + + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + /* Semaphores use xQueueGiveFromISR(), so pxQueue will not be a + semaphore or mutex. That means prvCopyDataToQueue() cannot result + in a task disinheriting a priority and prvCopyDataToQueue() can be + called here even though the disinherit function does not check if + the scheduler is suspended before accessing the ready lists. */ + ( void ) prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* The event list is not altered if the queue is locked. This will + be done when the queue is unlocked later. */ + if( cTxLock == queueUNLOCKED ) + { + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( prvNotifyQueueSetContainer( pxQueue, xCopyPosition ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting + to the queue set caused a higher priority task to + unblock. A context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so + record that a context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_QUEUE_SETS */ + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + pxQueue->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + /* Similar to xQueueGenericSendFromISR() but used with semaphores where the + item size is 0. Don't directly wake a task that was blocked on a queue + read, instead return a flag to say whether a context switch is required or + not (i.e. has a task with a higher priority than us been woken by this + post). */ + + configASSERT( pxQueue ); + + /* xQueueGenericSendFromISR() should be used instead of xQueueGiveFromISR() + if the item size is not 0. */ + configASSERT( pxQueue->uxItemSize == 0 ); + + /* Normally a mutex would not be given from an interrupt, especially if + there is a mutex holder, as priority inheritance makes no sense for an + interrupts, only tasks. */ + configASSERT( !( ( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) && ( pxQueue->u.xSemaphore.xMutexHolder != NULL ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* When the queue is used to implement a semaphore no data is ever + moved through the queue but it is still valid to see if the queue 'has + space'. */ + if( uxMessagesWaiting < pxQueue->uxLength ) + { + const int8_t cTxLock = pxQueue->cTxLock; + + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + /* A task can only have an inherited priority if it is a mutex + holder - and if there is a mutex holder then the mutex cannot be + given from an ISR. As this is the ISR version of the function it + can be assumed there is no mutex holder and no need to determine if + priority disinheritance is needed. Simply increase the count of + messages (semaphores) available. */ + pxQueue->uxMessagesWaiting = uxMessagesWaiting + ( UBaseType_t ) 1; + + /* The event list is not altered if the queue is locked. This will + be done when the queue is unlocked later. */ + if( cTxLock == queueUNLOCKED ) + { + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( prvNotifyQueueSetContainer( pxQueue, queueSEND_TO_BACK ) != pdFALSE ) + { + /* The semaphore is a member of a queue set, and + posting to the queue set caused a higher priority + task to unblock. A context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so + record that a context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_QUEUE_SETS */ + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + pxQueue->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + + /* Check the pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* The buffer into which data is received can only be NULL if the data size + is zero (so no data is copied into the buffer. */ + configASSERT( !( ( ( pvBuffer ) == NULL ) && ( ( pxQueue )->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Data available, remove one item. */ + prvCopyDataFromQueue( pxQueue, pvBuffer ); + traceQUEUE_RECEIVE( pxQueue ); + pxQueue->uxMessagesWaiting = uxMessagesWaiting - ( UBaseType_t ) 1; + + /* There is now space in the queue, were any tasks waiting to + post to the queue? If so, unblock the highest priority waiting + task. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* The timeout has not expired. If the queue is still empty place + the task on the list of tasks waiting to receive from the queue. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The queue contains data again. Loop back to try and read the + data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* Timed out. If there is no data in the queue exit, otherwise loop + back and attempt to read the data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +Queue_t * const pxQueue = xQueue; + +#if( configUSE_MUTEXES == 1 ) + BaseType_t xInheritanceOccurred = pdFALSE; +#endif + + /* Check the queue pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* Check this really is a semaphore, in which case the item size will be + 0. */ + configASSERT( pxQueue->uxItemSize == 0 ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Semaphores are queues with an item size of 0, and where the + number of messages in the queue is the semaphore's count value. */ + const UBaseType_t uxSemaphoreCount = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxSemaphoreCount > ( UBaseType_t ) 0 ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* Semaphores are queues with a data size of zero and where the + messages waiting is the semaphore's count. Reduce the count. */ + pxQueue->uxMessagesWaiting = uxSemaphoreCount - ( UBaseType_t ) 1; + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->u.xSemaphore.xMutexHolder = pvTaskIncrementMutexHeldCount(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_MUTEXES */ + + /* Check to see if other tasks are blocked waiting to give the + semaphore, and if so, unblock the highest priority such task. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* For inheritance to have occurred there must have been an + initial timeout, and an adjusted timeout cannot become 0, as + if it were 0 the function would have exited. */ + #if( configUSE_MUTEXES == 1 ) + { + configASSERT( xInheritanceOccurred == pdFALSE ); + } + #endif /* configUSE_MUTEXES */ + + /* The semaphore count was 0 and no block time is specified + (or the block time has expired) so exit now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The semaphore count was 0 and a block time was specified + so configure the timeout structure ready to block. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can give to and take from the semaphore + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* A block time is specified and not expired. If the semaphore + count is 0 then enter the Blocked state to wait for a semaphore to + become available. As semaphores are implemented with queues the + queue being empty is equivalent to the semaphore count being 0. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + taskENTER_CRITICAL(); + { + xInheritanceOccurred = xTaskPriorityInherit( pxQueue->u.xSemaphore.xMutexHolder ); + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* There was no timeout and the semaphore count was not 0, so + attempt to take the semaphore again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* Timed out. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* If the semaphore count is 0 exit now as the timeout has + expired. Otherwise return to attempt to take the semaphore that is + known to be available. As semaphores are implemented by queues the + queue being empty is equivalent to the semaphore count being 0. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + #if ( configUSE_MUTEXES == 1 ) + { + /* xInheritanceOccurred could only have be set if + pxQueue->uxQueueType == queueQUEUE_IS_MUTEX so no need to + test the mutex type again to check it is actually a mutex. */ + if( xInheritanceOccurred != pdFALSE ) + { + taskENTER_CRITICAL(); + { + UBaseType_t uxHighestWaitingPriority; + + /* This task blocking on the mutex caused another + task to inherit this task's priority. Now this task + has timed out the priority should be disinherited + again, but only as low as the next highest priority + task that is waiting for the same mutex. */ + uxHighestWaitingPriority = prvGetDisinheritPriorityAfterTimeout( pxQueue ); + vTaskPriorityDisinheritAfterTimeout( pxQueue->u.xSemaphore.xMutexHolder, uxHighestWaitingPriority ); + } + taskEXIT_CRITICAL(); + } + } + #endif /* configUSE_MUTEXES */ + + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) +{ +BaseType_t xEntryTimeSet = pdFALSE; +TimeOut_t xTimeOut; +int8_t *pcOriginalReadPosition; +Queue_t * const pxQueue = xQueue; + + /* Check the pointer is not NULL. */ + configASSERT( ( pxQueue ) ); + + /* The buffer into which data is received can only be NULL if the data size + is zero (so no data is copied into the buffer. */ + configASSERT( !( ( ( pvBuffer ) == NULL ) && ( ( pxQueue )->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* Cannot block if the scheduler is suspended. */ + #if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + { + configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) ); + } + #endif + + + /*lint -save -e904 This function relaxes the coding standard somewhat to + allow return statements within the function itself. This is done in the + interest of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Is there data in the queue now? To be running the calling task + must be the highest priority task wanting to access the queue. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Remember the read position so it can be reset after the data + is read from the queue as this function is only peeking the + data, not removing it. */ + pcOriginalReadPosition = pxQueue->u.xQueue.pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + traceQUEUE_PEEK( pxQueue ); + + /* The data is not being removed, so reset the read pointer. */ + pxQueue->u.xQueue.pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + queueYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( TickType_t ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_PEEK_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure ready to enter the blocked + state. */ + vTaskInternalSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + else + { + /* Entry time was already set. */ + mtCOVERAGE_TEST_MARKER(); + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + /* Timeout has not expired yet, check to see if there is data in the + queue now, and if not enter the Blocked state to wait for data. */ + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_PEEK( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* There is data in the queue now, so don't enter the blocked + state, instead return to try and obtain the data. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. If there is still no data in the queue + exit, otherwise go back and try to read the data again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceQUEUE_PEEK_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } /*lint -restore */ +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + const UBaseType_t uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + /* Cannot block in an ISR, so check there is data available. */ + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + const int8_t cRxLock = pxQueue->cRxLock; + + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + pxQueue->uxMessagesWaiting = uxMessagesWaiting - ( UBaseType_t ) 1; + + /* If the queue is locked the event list will not be modified. + Instead update the lock count so the task that unlocks the queue + will know that an ISR has removed data while the queue was + locked. */ + if( cRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + pxQueue->cRxLock = ( int8_t ) ( cRxLock + 1 ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue, void * const pvBuffer ) +{ +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; +int8_t *pcOriginalReadPosition; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) ); + configASSERT( pxQueue->uxItemSize != 0 ); /* Can't peek a semaphore. */ + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* Cannot block in an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + traceQUEUE_PEEK_FROM_ISR( pxQueue ); + + /* Remember the read position so it can be reset as nothing is + actually being removed from the queue. */ + pcOriginalReadPosition = pxQueue->u.xQueue.pcReadFrom; + prvCopyDataFromQueue( pxQueue, pvBuffer ); + pxQueue->u.xQueue.pcReadFrom = pcOriginalReadPosition; + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; + + configASSERT( xQueue ); + + taskENTER_CRITICAL(); + { + uxReturn = ( ( Queue_t * ) xQueue )->uxMessagesWaiting; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + uxReturn = pxQueue->uxLength - pxQueue->uxMessagesWaiting; + } + taskEXIT_CRITICAL(); + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue ) +{ +UBaseType_t uxReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */ +/*-----------------------------------------------------------*/ + +void vQueueDelete( QueueHandle_t xQueue ) +{ +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + traceQUEUE_DELETE( pxQueue ); + + #if ( configQUEUE_REGISTRY_SIZE > 0 ) + { + vQueueUnregisterQueue( pxQueue ); + } + #endif + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) ) + { + /* The queue can only have been allocated dynamically - free it + again. */ + vPortFree( pxQueue ); + } + #elif( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + { + /* The queue could have been allocated statically or dynamically, so + check before attempting to free the memory. */ + if( pxQueue->ucStaticallyAllocated == ( uint8_t ) pdFALSE ) + { + vPortFree( pxQueue ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #else + { + /* The queue must have been statically allocated, so is not going to be + deleted. Avoid compiler warnings about the unused parameter. */ + ( void ) pxQueue; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue ) + { + return ( ( Queue_t * ) xQueue )->uxQueueNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) + { + ( ( Queue_t * ) xQueue )->uxQueueNumber = uxQueueNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + uint8_t ucQueueGetQueueType( QueueHandle_t xQueue ) + { + return ( ( Queue_t * ) xQueue )->ucQueueType; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if( configUSE_MUTEXES == 1 ) + + static UBaseType_t prvGetDisinheritPriorityAfterTimeout( const Queue_t * const pxQueue ) + { + UBaseType_t uxHighestPriorityOfWaitingTasks; + + /* If a task waiting for a mutex causes the mutex holder to inherit a + priority, but the waiting task times out, then the holder should + disinherit the priority - but only down to the highest priority of any + other tasks that are waiting for the same mutex. For this purpose, + return the priority of the highest priority task that is waiting for the + mutex. */ + if( listCURRENT_LIST_LENGTH( &( pxQueue->xTasksWaitingToReceive ) ) > 0U ) + { + uxHighestPriorityOfWaitingTasks = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) listGET_ITEM_VALUE_OF_HEAD_ENTRY( &( pxQueue->xTasksWaitingToReceive ) ); + } + else + { + uxHighestPriorityOfWaitingTasks = tskIDLE_PRIORITY; + } + + return uxHighestPriorityOfWaitingTasks; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition ) +{ +BaseType_t xReturn = pdFALSE; +UBaseType_t uxMessagesWaiting; + + /* This function is called from a critical section. */ + + uxMessagesWaiting = pxQueue->uxMessagesWaiting; + + if( pxQueue->uxItemSize == ( UBaseType_t ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + xReturn = xTaskPriorityDisinherit( pxQueue->u.xSemaphore.xMutexHolder ); + pxQueue->u.xSemaphore.xMutexHolder = NULL; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_MUTEXES */ + } + else if( xPosition == queueSEND_TO_BACK ) + { + ( void ) memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 !e9087 MISRA exception as the casts are only redundant for some ports, plus previous logic ensures a null pointer can only be passed to memcpy() if the copy size is 0. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. */ + pxQueue->pcWriteTo += pxQueue->uxItemSize; /*lint !e9016 Pointer arithmetic on char types ok, especially in this use case where it is the clearest way of conveying intent. */ + if( pxQueue->pcWriteTo >= pxQueue->u.xQueue.pcTail ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */ + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + ( void ) memcpy( ( void * ) pxQueue->u.xQueue.pcReadFrom, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e9087 !e418 MISRA exception as the casts are only redundant for some ports. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. Assert checks null pointer only used when length is 0. */ + pxQueue->u.xQueue.pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom < pxQueue->pcHead ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */ + { + pxQueue->u.xQueue.pcReadFrom = ( pxQueue->u.xQueue.pcTail - pxQueue->uxItemSize ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xPosition == queueOVERWRITE ) + { + if( uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* An item is not being added but overwritten, so subtract + one from the recorded number of items in the queue so when + one is added again below the number of recorded items remains + correct. */ + --uxMessagesWaiting; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + pxQueue->uxMessagesWaiting = uxMessagesWaiting + ( UBaseType_t ) 1; + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer ) +{ + if( pxQueue->uxItemSize != ( UBaseType_t ) 0 ) + { + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; /*lint !e9016 Pointer arithmetic on char types ok, especially in this use case where it is the clearest way of conveying intent. */ + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) /*lint !e946 MISRA exception justified as use of the relational operator is the cleanest solutions. */ + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 !e9087 MISRA exception as the casts are only redundant for some ports. Also previous logic ensures a null pointer can only be passed to memcpy() when the count is 0. Cast to void required by function signature and safe as no alignment requirement and copy length specified in bytes. */ + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( Queue_t * const pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + int8_t cTxLock = pxQueue->cTxLock; + + /* See if data was added to the queue while it was locked. */ + while( cTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + #if ( configUSE_QUEUE_SETS == 1 ) + { + if( pxQueue->pxQueueSetContainer != NULL ) + { + if( prvNotifyQueueSetContainer( pxQueue, queueSEND_TO_BACK ) != pdFALSE ) + { + /* The queue is a member of a queue set, and posting to + the queue set caused a higher priority task to unblock. + A context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* Tasks that are removed from the event list will get + added to the pending ready list as the scheduler is still + suspended. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + break; + } + } + } + #else /* configUSE_QUEUE_SETS */ + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that + a context switch is required. */ + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + break; + } + } + #endif /* configUSE_QUEUE_SETS */ + + --cTxLock; + } + + pxQueue->cTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + int8_t cRxLock = pxQueue->cRxLock; + + while( cRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + --cRxLock; + } + else + { + break; + } + } + + pxQueue->cRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue ) +{ +BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue ) +{ +BaseType_t xReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ +/*-----------------------------------------------------------*/ + +static BaseType_t prvIsQueueFull( const Queue_t *pxQueue ) +{ +BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting == pxQueue->uxLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue ) +{ +BaseType_t xReturn; +Queue_t * const pxQueue = xQueue; + + configASSERT( pxQueue ); + if( pxQueue->uxMessagesWaiting == pxQueue->uxLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( TickType_t ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( TickType_t ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + portENABLE_INTERRUPTS(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --( pxQueue->uxMessagesWaiting ); + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken ) + { + Queue_t * const pxQueue = xQueue; + + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( xCoRoutinePreviouslyWoken == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCoRoutinePreviouslyWoken; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_CO_ROUTINES == 1 ) + + BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxCoRoutineWoken ) + { + BaseType_t xReturn; + Queue_t * const pxQueue = xQueue; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->u.xQueue.pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->u.xQueue.pcReadFrom >= pxQueue->u.xQueue.pcTail ) + { + pxQueue->u.xQueue.pcReadFrom = pxQueue->pcHead; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --( pxQueue->uxMessagesWaiting ); + ( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.xQueue.pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( ( *pxCoRoutineWoken ) == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif /* configUSE_CO_ROUTINES */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcQueueName ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + + traceQUEUE_REGISTRY_ADD( xQueue, pcQueueName ); + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + const char *pcQueueGetName( QueueHandle_t xQueue ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t ux; + const char *pcReturn = NULL; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + + /* Note there is nothing here to protect against another task adding or + removing entries from the registry while it is being searched. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + pcReturn = xQueueRegistry[ ux ].pcQueueName; + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return pcReturn; + } /*lint !e818 xQueue cannot be a pointer to const because it is a typedef. */ + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configQUEUE_REGISTRY_SIZE > 0 ) + + void vQueueUnregisterQueue( QueueHandle_t xQueue ) + { + UBaseType_t ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + + /* Set the handle to NULL to ensure the same queue handle cannot + appear in the registry twice if it is added, removed, then + added again. */ + xQueueRegistry[ ux ].xHandle = ( QueueHandle_t ) 0; + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + } /*lint !e818 xQueue could not be pointer to const because it is a typedef. */ + +#endif /* configQUEUE_REGISTRY_SIZE */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TIMERS == 1 ) + + void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) + { + Queue_t * const pxQueue = xQueue; + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait, xWaitIndefinitely ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + prvUnlockQueue( pxQueue ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +#if( ( configUSE_QUEUE_SETS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength ) + { + QueueSetHandle_t pxQueue; + + pxQueue = xQueueGenericCreate( uxEventQueueLength, ( UBaseType_t ) sizeof( Queue_t * ), queueQUEUE_TYPE_SET ); + + return pxQueue; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) + { + BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + if( ( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer != NULL ) + { + /* Cannot add a queue/semaphore to more than one queue set. */ + xReturn = pdFAIL; + } + else if( ( ( Queue_t * ) xQueueOrSemaphore )->uxMessagesWaiting != ( UBaseType_t ) 0 ) + { + /* Cannot add a queue/semaphore to a queue set if there are already + items in the queue/semaphore. */ + xReturn = pdFAIL; + } + else + { + ( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer = xQueueSet; + xReturn = pdPASS; + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) + { + BaseType_t xReturn; + Queue_t * const pxQueueOrSemaphore = ( Queue_t * ) xQueueOrSemaphore; + + if( pxQueueOrSemaphore->pxQueueSetContainer != xQueueSet ) + { + /* The queue was not a member of the set. */ + xReturn = pdFAIL; + } + else if( pxQueueOrSemaphore->uxMessagesWaiting != ( UBaseType_t ) 0 ) + { + /* It is dangerous to remove a queue from a set when the queue is + not empty because the queue set will still hold pending events for + the queue. */ + xReturn = pdFAIL; + } + else + { + taskENTER_CRITICAL(); + { + /* The queue is no longer contained in the set. */ + pxQueueOrSemaphore->pxQueueSetContainer = NULL; + } + taskEXIT_CRITICAL(); + xReturn = pdPASS; + } + + return xReturn; + } /*lint !e818 xQueueSet could not be declared as pointing to const as it is a typedef. */ + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, TickType_t const xTicksToWait ) + { + QueueSetMemberHandle_t xReturn = NULL; + + ( void ) xQueueReceive( ( QueueHandle_t ) xQueueSet, &xReturn, xTicksToWait ); /*lint !e961 Casting from one typedef to another is not redundant. */ + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet ) + { + QueueSetMemberHandle_t xReturn = NULL; + + ( void ) xQueueReceiveFromISR( ( QueueHandle_t ) xQueueSet, &xReturn, NULL ); /*lint !e961 Casting from one typedef to another is not redundant. */ + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_QUEUE_SETS == 1 ) + + static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue, const BaseType_t xCopyPosition ) + { + Queue_t *pxQueueSetContainer = pxQueue->pxQueueSetContainer; + BaseType_t xReturn = pdFALSE; + + /* This function must be called form a critical section. */ + + configASSERT( pxQueueSetContainer ); + configASSERT( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength ); + + if( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength ) + { + const int8_t cTxLock = pxQueueSetContainer->cTxLock; + + traceQUEUE_SEND( pxQueueSetContainer ); + + /* The data copied is the handle of the queue that contains data. */ + xReturn = prvCopyDataToQueue( pxQueueSetContainer, &pxQueue, xCopyPosition ); + + if( cTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + pxQueueSetContainer->cTxLock = ( int8_t ) ( cTxLock + 1 ); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_QUEUE_SETS */ + + + + + + + + + + + + diff --git a/lib/FreeRTOS-SAMD51/src/queue.h b/lib/FreeRTOS-SAMD51/src/queue.h new file mode 100644 index 0000000..6b76efc --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/queue.h @@ -0,0 +1,1655 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "task.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate() + * returns an QueueHandle_t variable that can then be used as a parameter to + * xQueueSend(), xQueueReceive(), etc. + */ +struct QueueDefinition; /* Using old naming convention so as not to break kernel aware debuggers. */ +typedef struct QueueDefinition * QueueHandle_t; + +/** + * Type by which queue sets are referenced. For example, a call to + * xQueueCreateSet() returns an xQueueSet variable that can then be used as a + * parameter to xQueueSelectFromSet(), xQueueAddToSet(), etc. + */ +typedef struct QueueDefinition * QueueSetHandle_t; + +/** + * Queue sets can contain both queues and semaphores, so the + * QueueSetMemberHandle_t is defined as a type to be used where a parameter or + * return value can be either an QueueHandle_t or an SemaphoreHandle_t. + */ +typedef struct QueueDefinition * QueueSetMemberHandle_t; + +/* For internal use only. */ +#define queueSEND_TO_BACK ( ( BaseType_t ) 0 ) +#define queueSEND_TO_FRONT ( ( BaseType_t ) 1 ) +#define queueOVERWRITE ( ( BaseType_t ) 2 ) + +/* For internal use only. These definitions *must* match those in queue.c. */ +#define queueQUEUE_TYPE_BASE ( ( uint8_t ) 0U ) +#define queueQUEUE_TYPE_SET ( ( uint8_t ) 0U ) +#define queueQUEUE_TYPE_MUTEX ( ( uint8_t ) 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( ( uint8_t ) 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( ( uint8_t ) 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( ( uint8_t ) 4U ) + +/** + * queue. h + *
+ QueueHandle_t xQueueCreate(
+							  UBaseType_t uxQueueLength,
+							  UBaseType_t uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance, and returns a handle by which the new queue + * can be referenced. + * + * Internally, within the FreeRTOS implementation, queues use two blocks of + * memory. The first block is used to hold the queue's data structures. The + * second block is used to hold items placed into the queue. If a queue is + * created using xQueueCreate() then both blocks of memory are automatically + * dynamically allocated inside the xQueueCreate() function. (see + * http://www.freertos.org/a00111.html). If a queue is created using + * xQueueCreateStatic() then the application writer must provide the memory that + * will get used by the queue. xQueueCreateStatic() therefore allows a queue to + * be created without using any dynamic memory allocation. + * + * http://www.FreeRTOS.org/Embedded-RTOS-Queues.html + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( ( uxQueueLength ), ( uxItemSize ), ( queueQUEUE_TYPE_BASE ) ) +#endif + +/** + * queue. h + *
+ QueueHandle_t xQueueCreateStatic(
+							  UBaseType_t uxQueueLength,
+							  UBaseType_t uxItemSize,
+							  uint8_t *pucQueueStorageBuffer,
+							  StaticQueue_t *pxQueueBuffer
+						  );
+ * 
+ * + * Creates a new queue instance, and returns a handle by which the new queue + * can be referenced. + * + * Internally, within the FreeRTOS implementation, queues use two blocks of + * memory. The first block is used to hold the queue's data structures. The + * second block is used to hold items placed into the queue. If a queue is + * created using xQueueCreate() then both blocks of memory are automatically + * dynamically allocated inside the xQueueCreate() function. (see + * http://www.freertos.org/a00111.html). If a queue is created using + * xQueueCreateStatic() then the application writer must provide the memory that + * will get used by the queue. xQueueCreateStatic() therefore allows a queue to + * be created without using any dynamic memory allocation. + * + * http://www.FreeRTOS.org/Embedded-RTOS-Queues.html + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @param pucQueueStorageBuffer If uxItemSize is not zero then + * pucQueueStorageBuffer must point to a uint8_t array that is at least large + * enough to hold the maximum number of items that can be in the queue at any + * one time - which is ( uxQueueLength * uxItemsSize ) bytes. If uxItemSize is + * zero then pucQueueStorageBuffer can be NULL. + * + * @param pxQueueBuffer Must point to a variable of type StaticQueue_t, which + * will be used to hold the queue's data structure. + * + * @return If the queue is created then a handle to the created queue is + * returned. If pxQueueBuffer is NULL then NULL is returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ #define QUEUE_LENGTH 10
+ #define ITEM_SIZE sizeof( uint32_t )
+
+ // xQueueBuffer will hold the queue structure.
+ StaticQueue_t xQueueBuffer;
+
+ // ucQueueStorage will hold the items posted to the queue.  Must be at least
+ // [(queue length) * ( queue item size)] bytes long.
+ uint8_t ucQueueStorage[ QUEUE_LENGTH * ITEM_SIZE ];
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( QUEUE_LENGTH, // The number of items the queue can hold.
+							ITEM_SIZE	  // The size of each item in the queue
+							&( ucQueueStorage[ 0 ] ), // The buffer that will hold the items in the queue.
+							&xQueueBuffer ); // The buffer that will hold the queue structure.
+
+	// The queue is guaranteed to be created successfully as no dynamic memory
+	// allocation is used.  Therefore xQueue1 is now a handle to a valid queue.
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreateStatic xQueueCreateStatic + * \ingroup QueueManagement + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xQueueCreateStatic( uxQueueLength, uxItemSize, pucQueueStorage, pxQueueBuffer ) xQueueGenericCreateStatic( ( uxQueueLength ), ( uxItemSize ), ( pucQueueStorage ), ( pxQueueBuffer ), ( queueQUEUE_TYPE_BASE ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * queue. h + *
+ BaseType_t xQueueSendToToFront(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * 
+ * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ BaseType_t xQueueSendToBack(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueSend(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  TickType_t xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueOverwrite(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue
+						 );
+ * 
+ * + * Only for use with queues that have a length of one - so the queue is either + * empty or full. + * + * Post an item on a queue. If the queue is already full then overwrite the + * value held in the queue. The item is queued by copy, not by reference. + * + * This function must not be called from an interrupt service routine. + * See xQueueOverwriteFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle of the queue to which the data is being sent. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @return xQueueOverwrite() is a macro that calls xQueueGenericSend(), and + * therefore has the same return values as xQueueSendToFront(). However, pdPASS + * is the only value that can be returned because xQueueOverwrite() will write + * to the queue even when the queue is already full. + * + * Example usage: +
+
+ void vFunction( void *pvParameters )
+ {
+ QueueHandle_t xQueue;
+ uint32_t ulVarToSend, ulValReceived;
+
+	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwrite() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+
+	// Write the value 10 to the queue using xQueueOverwrite().
+	ulVarToSend = 10;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// Peeking the queue should now return 10, but leave the value 10 in
+	// the queue.  A block time of zero is used as it is known that the
+	// queue holds a value.
+	ulValReceived = 0;
+	xQueuePeek( xQueue, &ulValReceived, 0 );
+
+	if( ulValReceived != 10 )
+	{
+		// Error unless the item was removed by a different task.
+	}
+
+	// The queue is still full.  Use xQueueOverwrite() to overwrite the
+	// value held in the queue with 100.
+	ulVarToSend = 100;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// This time read from the queue, leaving the queue empty once more.
+	// A block time of 0 is used again.
+	xQueueReceive( xQueue, &ulValReceived, 0 );
+
+	// The value read should be the last value written, even though the
+	// queue was already full when the value was written.
+	if( ulValReceived != 100 )
+	{
+		// Error!
+	}
+
+	// ...
+}
+ 
+ * \defgroup xQueueOverwrite xQueueOverwrite + * \ingroup QueueManagement + */ +#define xQueueOverwrite( xQueue, pvItemToQueue ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), 0, queueOVERWRITE ) + + +/** + * queue. h + *
+ BaseType_t xQueueGenericSend(
+									QueueHandle_t xQueue,
+									const void * pvItemToQueue,
+									TickType_t xTicksToWait
+									BaseType_t xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueuePeek(
+							 QueueHandle_t xQueue,
+							 void * const pvBuffer,
+							 TickType_t xTicksToWait
+						 );
+ * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. See + * xQueuePeekFromISR() for an alternative that can be called from an interrupt + * service routine. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_PERIOD_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueuePeek xQueuePeek + * \ingroup QueueManagement + */ +BaseType_t xQueuePeek( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueuePeekFromISR(
+									QueueHandle_t xQueue,
+									void *pvBuffer,
+								);
+ * + * A version of xQueuePeek() that can be called from an interrupt service + * routine (ISR). + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * \defgroup xQueuePeekFromISR xQueuePeekFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueReceive(
+								 QueueHandle_t xQueue,
+								 void *pvBuffer,
+								 TickType_t xTicksToWait
+							);
+ * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_PERIOD_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +BaseType_t xQueueReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue );
+ * + * Return the number of free spaces available in a queue. This is equal to the + * number of items that can be sent to the queue before the queue becomes full + * if no items are removed. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of spaces available in the queue. + * + * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
void vQueueDelete( QueueHandle_t xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \defgroup vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueSendToFrontFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ BaseType_t xQueueSendToBackFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueOverwriteFromISR(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  BaseType_t *pxHigherPriorityTaskWoken
+						 );
+ * 
+ * + * A version of xQueueOverwrite() that can be used in an interrupt service + * routine (ISR). + * + * Only for use with queues that can hold a single item - so the queue is either + * empty or full. + * + * Post an item on a queue. If the queue is already full then overwrite the + * value held in the queue. The item is queued by copy, not by reference. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueOverwriteFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueOverwriteFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return xQueueOverwriteFromISR() is a macro that calls + * xQueueGenericSendFromISR(), and therefore has the same return values as + * xQueueSendToFrontFromISR(). However, pdPASS is the only value that can be + * returned because xQueueOverwriteFromISR() will write to the queue even when + * the queue is already full. + * + * Example usage: +
+
+ QueueHandle_t xQueue;
+
+ void vFunction( void *pvParameters )
+ {
+ 	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwriteFromISR() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+}
+
+void vAnInterruptHandler( void )
+{
+// xHigherPriorityTaskWoken must be set to pdFALSE before it is used.
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+uint32_t ulVarToSend, ulValReceived;
+
+	// Write the value 10 to the queue using xQueueOverwriteFromISR().
+	ulVarToSend = 10;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// The queue is full, but calling xQueueOverwriteFromISR() again will still
+	// pass because the value held in the queue will be overwritten with the
+	// new value.
+	ulVarToSend = 100;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// Reading from the queue will now return 100.
+
+	// ...
+
+	if( xHigherPrioritytaskWoken == pdTRUE )
+	{
+		// Writing to the queue caused a task to unblock and the unblocked task
+		// has a priority higher than or equal to the priority of the currently
+		// executing task (the task this interrupt interrupted).  Perform a context
+		// switch so this interrupt returns directly to the unblocked task.
+		portYIELD_FROM_ISR(); // or portEND_SWITCHING_ISR() depending on the port.
+	}
+}
+ 
+ * \defgroup xQueueOverwriteFromISR xQueueOverwriteFromISR + * \ingroup QueueManagement + */ +#define xQueueOverwriteFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueOVERWRITE ) + +/** + * queue. h + *
+ BaseType_t xQueueSendFromISR(
+									 QueueHandle_t xQueue,
+									 const void *pvItemToQueue,
+									 BaseType_t *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		portYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ BaseType_t xQueueGenericSendFromISR(
+										   QueueHandle_t		xQueue,
+										   const	void	*pvItemToQueue,
+										   BaseType_t	*pxHigherPriorityTaskWoken,
+										   BaseType_t	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. xQueueGiveFromISR() is an + * equivalent for use by semaphores that don't actually copy any data. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * queue. h + *
+ BaseType_t xQueueReceiveFromISR(
+									   QueueHandle_t	xQueue,
+									   void	*pvBuffer,
+									   BaseType_t *pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param xQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ QueueHandle_t xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const TickType_t xTicksToWait = ( TickType_t )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xTicksToWait ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ BaseType_t xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/* + * Utilities to query queues that are safe to use from an ISR. These utilities + * should be used only from within an ISR, or within a critical section. + */ +BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken ); +BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxTaskWoken ); +BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait ); +BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex(), + * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling + * these functions directly. + */ +QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateMutexStatic( const uint8_t ucQueueType, StaticQueue_t *pxStaticQueue ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) PRIVILEGED_FUNCTION; +QueueHandle_t xQueueCreateCountingSemaphoreStatic( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount, StaticQueue_t *pxStaticQueue ) PRIVILEGED_FUNCTION; +BaseType_t xQueueSemaphoreTake( QueueHandle_t xQueue, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +TaskHandle_t xQueueGetMutexHolder( QueueHandle_t xSemaphore ) PRIVILEGED_FUNCTION; +TaskHandle_t xQueueGetMutexHolderFromISR( QueueHandle_t xSemaphore ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGiveMutexRecursive( QueueHandle_t xMutex ) PRIVILEGED_FUNCTION; + +/* + * Reset a queue back to its original empty state. The return value is now + * obsolete and is always set to pdPASS. + */ +#define xQueueReset( xQueue ) xQueueGenericReset( xQueue, pdFALSE ) + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. The queue registry only + * stores a pointer to the string - so the string must be persistent (global or + * preferably in ROM/Flash), not on the stack. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcQueueName ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +#endif + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger, and vQueueUnregisterQueue() to + * remove the queue, semaphore or mutex from the register. If you are not using + * a kernel aware debugger then this function can be ignored. + * + * @param xQueue The handle of the queue being removed from the registry. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + void vQueueUnregisterQueue( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call pcQueueGetName() to look + * up and return the name of a queue in the queue registry from the queue's + * handle. + * + * @param xQueue The handle of the queue the name of which will be returned. + * @return If the queue is in the registry then a pointer to the name of the + * queue is returned. If the queue is not in the registry then NULL is + * returned. + */ +#if( configQUEUE_REGISTRY_SIZE > 0 ) + const char *pcQueueGetName( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +#endif + +/* + * Generic version of the function used to creaet a queue using dynamic memory + * allocation. This is called by other functions and macros that create other + * RTOS objects that use the queue structure as their base. + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +#endif + +/* + * Generic version of the function used to creaet a queue using dynamic memory + * allocation. This is called by other functions and macros that create other + * RTOS objects that use the queue structure as their base. + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + QueueHandle_t xQueueGenericCreateStatic( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, uint8_t *pucQueueStorage, StaticQueue_t *pxStaticQueue, const uint8_t ucQueueType ) PRIVILEGED_FUNCTION; +#endif + +/* + * Queue sets provide a mechanism to allow a task to block (pend) on a read + * operation from multiple queues or semaphores simultaneously. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * A queue set must be explicitly created using a call to xQueueCreateSet() + * before it can be used. Once created, standard FreeRTOS queues and semaphores + * can be added to the set using calls to xQueueAddToSet(). + * xQueueSelectFromSet() is then used to determine which, if any, of the queues + * or semaphores contained in the set is in a state where a queue read or + * semaphore take operation would be successful. + * + * Note 1: See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html + * for reasons why queue sets are very rarely needed in practice as there are + * simpler methods of blocking on multiple objects. + * + * Note 2: Blocking on a queue set that contains a mutex will not cause the + * mutex holder to inherit the priority of the blocked task. + * + * Note 3: An additional 4 bytes of RAM is required for each space in a every + * queue added to a queue set. Therefore counting semaphores that have a high + * maximum count value should not be added to a queue set. + * + * Note 4: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param uxEventQueueLength Queue sets store events that occur on + * the queues and semaphores contained in the set. uxEventQueueLength specifies + * the maximum number of events that can be queued at once. To be absolutely + * certain that events are not lost uxEventQueueLength should be set to the + * total sum of the length of the queues added to the set, where binary + * semaphores and mutexes have a length of 1, and counting semaphores have a + * length set by their maximum count value. Examples: + * + If a queue set is to hold a queue of length 5, another queue of length 12, + * and a binary semaphore, then uxEventQueueLength should be set to + * (5 + 12 + 1), or 18. + * + If a queue set is to hold three binary semaphores then uxEventQueueLength + * should be set to (1 + 1 + 1 ), or 3. + * + If a queue set is to hold a counting semaphore that has a maximum count of + * 5, and a counting semaphore that has a maximum count of 3, then + * uxEventQueueLength should be set to (5 + 3), or 8. + * + * @return If the queue set is created successfully then a handle to the created + * queue set is returned. Otherwise NULL is returned. + */ +QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength ) PRIVILEGED_FUNCTION; + +/* + * Adds a queue or semaphore to a queue set that was previously created by a + * call to xQueueCreateSet(). + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * Note 1: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param xQueueOrSemaphore The handle of the queue or semaphore being added to + * the queue set (cast to an QueueSetMemberHandle_t type). + * + * @param xQueueSet The handle of the queue set to which the queue or semaphore + * is being added. + * + * @return If the queue or semaphore was successfully added to the queue set + * then pdPASS is returned. If the queue could not be successfully added to the + * queue set because it is already a member of a different queue set then pdFAIL + * is returned. + */ +BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* + * Removes a queue or semaphore from a queue set. A queue or semaphore can only + * be removed from a set if the queue or semaphore is empty. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * @param xQueueOrSemaphore The handle of the queue or semaphore being removed + * from the queue set (cast to an QueueSetMemberHandle_t type). + * + * @param xQueueSet The handle of the queue set in which the queue or semaphore + * is included. + * + * @return If the queue or semaphore was successfully removed from the queue set + * then pdPASS is returned. If the queue was not in the queue set, or the + * queue (or semaphore) was not empty, then pdFAIL is returned. + */ +BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* + * xQueueSelectFromSet() selects from the members of a queue set a queue or + * semaphore that either contains data (in the case of a queue) or is available + * to take (in the case of a semaphore). xQueueSelectFromSet() effectively + * allows a task to block (pend) on a read operation on all the queues and + * semaphores in a queue set simultaneously. + * + * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this + * function. + * + * Note 1: See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html + * for reasons why queue sets are very rarely needed in practice as there are + * simpler methods of blocking on multiple objects. + * + * Note 2: Blocking on a queue set that contains a mutex will not cause the + * mutex holder to inherit the priority of the blocked task. + * + * Note 3: A receive (in the case of a queue) or take (in the case of a + * semaphore) operation must not be performed on a member of a queue set unless + * a call to xQueueSelectFromSet() has first returned a handle to that set member. + * + * @param xQueueSet The queue set on which the task will (potentially) block. + * + * @param xTicksToWait The maximum time, in ticks, that the calling task will + * remain in the Blocked state (with other tasks executing) to wait for a member + * of the queue set to be ready for a successful queue read or semaphore take + * operation. + * + * @return xQueueSelectFromSet() will return the handle of a queue (cast to + * a QueueSetMemberHandle_t type) contained in the queue set that contains data, + * or the handle of a semaphore (cast to a QueueSetMemberHandle_t type) contained + * in the queue set that is available, or NULL if no such queue or semaphore + * exists before before the specified block time expires. + */ +QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * A version of xQueueSelectFromSet() that can be used from an ISR. + */ +QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION; + +/* Not public API functions. */ +void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION; +BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) PRIVILEGED_FUNCTION; +void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) PRIVILEGED_FUNCTION; +UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; +uint8_t ucQueueGetQueueType( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION; + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.c b/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.c new file mode 100644 index 0000000..062f51c --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.c @@ -0,0 +1,20 @@ + +#include "runTimeStats_hooks.h" + +//************************************************************************ + +// setup the hardware timer to use as a counter +void vMainConfigureTimerForRunTimeStats( void ) +{ + // do nothing, will use the arduino systick timer + // can change this if you want +} + +// will return the counter value to generate run time stats +unsigned long ulMainGetRunTimeCounterValue( void ) +{ + return micros(); //use already setup arduino systick timer +} + +//************************************************************************ + diff --git a/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.h b/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.h new file mode 100644 index 0000000..90f2d70 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/runTimeStats_hooks.h @@ -0,0 +1,24 @@ + +#include +#include "FreeRTOS.h" + +#ifndef RUN_TIME_STATS_HOOKS_H +#define RUN_TIME_STATS_HOOKS_H + +#ifdef __cplusplus +extern "C" +{ +#endif + + //************************************************** + // function prototypes + //************************************************** + + void vMainConfigureTimerForRunTimeStats( void ); + unsigned long ulMainGetRunTimeCounterValue( void ); + +#ifdef __cplusplus +} +#endif + +#endif // end RUN_TIME_STATS_HOOKS_H diff --git a/lib/FreeRTOS-SAMD51/src/semphr.h b/lib/FreeRTOS-SAMD51/src/semphr.h new file mode 100644 index 0000000..2c106ea --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/semphr.h @@ -0,0 +1,1140 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include semphr.h" +#endif + +#include "queue.h" + +typedef QueueHandle_t SemaphoreHandle_t; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( uint8_t ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( uint8_t ) 0U ) +#define semGIVE_BLOCK_TIME ( ( TickType_t ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( SemaphoreHandle_t xSemaphore )
+ * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * This old vSemaphoreCreateBinary() macro is now deprecated in favour of the + * xSemaphoreCreateBinary() function. Note that binary semaphores created using + * the vSemaphoreCreateBinary() macro are created in a state such that the + * first call to 'take' the semaphore would pass, whereas binary semaphores + * created using xSemaphoreCreateBinary() are created in a state such that the + * the semaphore must first be 'given' before it can be 'taken'. + * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type SemaphoreHandle_t. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define vSemaphoreCreateBinary( xSemaphore ) \ + { \ + ( xSemaphore ) = xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + ( void ) xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateBinary( void )
+ * + * Creates a new binary semaphore instance, and returns a handle by which the + * new semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, binary semaphores use a block + * of memory, in which the semaphore structure is stored. If a binary semaphore + * is created using xSemaphoreCreateBinary() then the required memory is + * automatically dynamically allocated inside the xSemaphoreCreateBinary() + * function. (see http://www.freertos.org/a00111.html). If a binary semaphore + * is created using xSemaphoreCreateBinaryStatic() then the application writer + * must provide the memory. xSemaphoreCreateBinaryStatic() therefore allows a + * binary semaphore to be created without using any dynamic memory allocation. + * + * The old vSemaphoreCreateBinary() macro is now deprecated in favour of this + * xSemaphoreCreateBinary() function. Note that binary semaphores created using + * the vSemaphoreCreateBinary() macro are created in a state such that the + * first call to 'take' the semaphore would pass, whereas binary semaphores + * created using xSemaphoreCreateBinary() are created in a state such that the + * the semaphore must first be 'given' before it can be 'taken'. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @return Handle to the created semaphore, or NULL if the memory required to + * hold the semaphore's data structures could not be allocated. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateBinary().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateBinary();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateBinary xSemaphoreCreateBinary + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateBinary() xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateBinaryStatic( StaticSemaphore_t *pxSemaphoreBuffer )
+ * + * Creates a new binary semaphore instance, and returns a handle by which the + * new semaphore can be referenced. + * + * NOTE: In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a binary semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, binary semaphores use a block + * of memory, in which the semaphore structure is stored. If a binary semaphore + * is created using xSemaphoreCreateBinary() then the required memory is + * automatically dynamically allocated inside the xSemaphoreCreateBinary() + * function. (see http://www.freertos.org/a00111.html). If a binary semaphore + * is created using xSemaphoreCreateBinaryStatic() then the application writer + * must provide the memory. xSemaphoreCreateBinaryStatic() therefore allows a + * binary semaphore to be created without using any dynamic memory allocation. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param pxSemaphoreBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the semaphore's data structure, removing the + * need for the memory to be allocated dynamically. + * + * @return If the semaphore is created then a handle to the created semaphore is + * returned. If pxSemaphoreBuffer is NULL then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+ StaticSemaphore_t xSemaphoreBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateBinary().
+    // The semaphore's data structures will be placed in the xSemaphoreBuffer
+    // variable, the address of which is passed into the function.  The
+    // function's parameter is not NULL, so the function will not attempt any
+    // dynamic memory allocation, and therefore the function will not return
+    // return NULL.
+    xSemaphore = xSemaphoreCreateBinary( &xSemaphoreBuffer );
+
+    // Rest of task code goes here.
+ }
+ 
+ * \defgroup xSemaphoreCreateBinaryStatic xSemaphoreCreateBinaryStatic + * \ingroup Semaphores + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateBinaryStatic( pxStaticSemaphore ) xQueueGenericCreateStatic( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, NULL, pxStaticSemaphore, queueQUEUE_TYPE_BINARY_SEMAPHORE ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
xSemaphoreTake(
+ *                   SemaphoreHandle_t xSemaphore,
+ *                   TickType_t xBlockTime
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_PERIOD_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    xSemaphore = xSemaphoreCreateBinary();
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueSemaphoreTake( ( xSemaphore ), ( xBlockTime ) ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * SemaphoreHandle_t xMutex, + * TickType_t xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_PERIOD_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+            // xSemaphoreTakeRecursive() are made on the same mutex.  In real
+            // code these would not be just sequential calls as this would make
+            // no sense.  Instead the calls are likely to be buried inside
+            // a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+            // available to another task until it has also been given back
+            // three times.  Again it is unlikely that real code would have
+            // these calls sequentially, but instead buried in a more complex
+            // call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+            xSemaphoreGiveRecursive( xMutex );
+            xSemaphoreGiveRecursive( xMutex );
+
+            // Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#if( configUSE_RECURSIVE_MUTEXES == 1 ) + #define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) +#endif + +/** + * semphr. h + *
xSemaphoreGive( SemaphoreHandle_t xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    xSemaphore = vSemaphoreCreateBinary();
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( QueueHandle_t ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( SemaphoreHandle_t xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#if( configUSE_RECURSIVE_MUTEXES == 1 ) + #define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) +#endif + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to xSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static uint8_t ucLocalTickCount = 0;
+ static BaseType_t xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGiveFromISR( ( QueueHandle_t ) ( xSemaphore ), ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
+ xSemaphoreTakeFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to take a semaphore from an ISR. The semaphore must have + * previously been created with a call to xSemaphoreCreateBinary() or + * xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR, however taking a semaphore from an ISR + * is not a common operation. It is likely to only be useful when taking a + * counting semaphore when an interrupt is obtaining an object from a resource + * pool (when the semaphore count indicates the number of resources available). + * + * @param xSemaphore A handle to the semaphore being taken. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully taken, otherwise + * pdFALSE + */ +#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( QueueHandle_t ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateMutex( void )
+ * + * Creates a new mutex type semaphore instance, and returns a handle by which + * the new mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, mutex semaphores use a block + * of memory, in which the mutex structure is stored. If a mutex is created + * using xSemaphoreCreateMutex() then the required memory is automatically + * dynamically allocated inside the xSemaphoreCreateMutex() function. (see + * http://www.freertos.org/a00111.html). If a mutex is created using + * xSemaphoreCreateMutexStatic() then the application writer must provided the + * memory. xSemaphoreCreateMutexStatic() therefore allows a mutex to be created + * without using any dynamic memory allocation. + * + * Mutexes created using this function can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros must not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return If the mutex was successfully created then a handle to the created + * semaphore is returned. If there was not enough heap to allocate the mutex + * data structures then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateMutex xSemaphoreCreateMutex + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateMutexStatic( StaticSemaphore_t *pxMutexBuffer )
+ * + * Creates a new mutex type semaphore instance, and returns a handle by which + * the new mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, mutex semaphores use a block + * of memory, in which the mutex structure is stored. If a mutex is created + * using xSemaphoreCreateMutex() then the required memory is automatically + * dynamically allocated inside the xSemaphoreCreateMutex() function. (see + * http://www.freertos.org/a00111.html). If a mutex is created using + * xSemaphoreCreateMutexStatic() then the application writer must provided the + * memory. xSemaphoreCreateMutexStatic() therefore allows a mutex to be created + * without using any dynamic memory allocation. + * + * Mutexes created using this function can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros must not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @param pxMutexBuffer Must point to a variable of type StaticSemaphore_t, + * which will be used to hold the mutex's data structure, removing the need for + * the memory to be allocated dynamically. + * + * @return If the mutex was successfully created then a handle to the created + * mutex is returned. If pxMutexBuffer was NULL then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xMutexBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // A mutex cannot be used before it has been created.  xMutexBuffer is
+    // into xSemaphoreCreateMutexStatic() so no dynamic memory allocation is
+    // attempted.
+    xSemaphore = xSemaphoreCreateMutexStatic( &xMutexBuffer );
+
+    // As no dynamic memory allocation was performed, xSemaphore cannot be NULL,
+    // so there is no need to check it.
+ }
+ 
+ * \defgroup xSemaphoreCreateMutexStatic xSemaphoreCreateMutexStatic + * \ingroup Semaphores + */ + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateMutexStatic( pxMutexBuffer ) xQueueCreateMutexStatic( queueQUEUE_TYPE_MUTEX, ( pxMutexBuffer ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateRecursiveMutex( void )
+ * + * Creates a new recursive mutex type semaphore instance, and returns a handle + * by which the new recursive mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, recursive mutexs use a block + * of memory, in which the mutex structure is stored. If a recursive mutex is + * created using xSemaphoreCreateRecursiveMutex() then the required memory is + * automatically dynamically allocated inside the + * xSemaphoreCreateRecursiveMutex() function. (see + * http://www.freertos.org/a00111.html). If a recursive mutex is created using + * xSemaphoreCreateRecursiveMutexStatic() then the application writer must + * provide the memory that will get used by the mutex. + * xSemaphoreCreateRecursiveMutexStatic() therefore allows a recursive mutex to + * be created without using any dynamic memory allocation. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros must not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * SemaphoreHandle_t. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateRecursiveMutex xSemaphoreCreateRecursiveMutex + * \ingroup Semaphores + */ +#if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) ) + #define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateRecursiveMutexStatic( StaticSemaphore_t *pxMutexBuffer )
+ * + * Creates a new recursive mutex type semaphore instance, and returns a handle + * by which the new recursive mutex can be referenced. + * + * Internally, within the FreeRTOS implementation, recursive mutexs use a block + * of memory, in which the mutex structure is stored. If a recursive mutex is + * created using xSemaphoreCreateRecursiveMutex() then the required memory is + * automatically dynamically allocated inside the + * xSemaphoreCreateRecursiveMutex() function. (see + * http://www.freertos.org/a00111.html). If a recursive mutex is created using + * xSemaphoreCreateRecursiveMutexStatic() then the application writer must + * provide the memory that will get used by the mutex. + * xSemaphoreCreateRecursiveMutexStatic() therefore allows a recursive mutex to + * be created without using any dynamic memory allocation. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros must not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See xSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @param pxMutexBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the recursive mutex's data structure, + * removing the need for the memory to be allocated dynamically. + * + * @return If the recursive mutex was successfully created then a handle to the + * created recursive mutex is returned. If pxMutexBuffer was NULL then NULL is + * returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xMutexBuffer;
+
+ void vATask( void * pvParameters )
+ {
+    // A recursive semaphore cannot be used before it is created.  Here a
+    // recursive mutex is created using xSemaphoreCreateRecursiveMutexStatic().
+    // The address of xMutexBuffer is passed into the function, and will hold
+    // the mutexes data structures - so no dynamic memory allocation will be
+    // attempted.
+    xSemaphore = xSemaphoreCreateRecursiveMutexStatic( &xMutexBuffer );
+
+    // As no dynamic memory allocation was performed, xSemaphore cannot be NULL,
+    // so there is no need to check it.
+ }
+ 
+ * \defgroup xSemaphoreCreateRecursiveMutexStatic xSemaphoreCreateRecursiveMutexStatic + * \ingroup Semaphores + */ +#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) ) + #define xSemaphoreCreateRecursiveMutexStatic( pxStaticSemaphore ) xQueueCreateMutexStatic( queueQUEUE_TYPE_RECURSIVE_MUTEX, pxStaticSemaphore ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateCounting( UBaseType_t uxMaxCount, UBaseType_t uxInitialCount )
+ * + * Creates a new counting semaphore instance, and returns a handle by which the + * new counting semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a counting semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, counting semaphores use a + * block of memory, in which the counting semaphore structure is stored. If a + * counting semaphore is created using xSemaphoreCreateCounting() then the + * required memory is automatically dynamically allocated inside the + * xSemaphoreCreateCounting() function. (see + * http://www.freertos.org/a00111.html). If a counting semaphore is created + * using xSemaphoreCreateCountingStatic() then the application writer can + * instead optionally provide the memory that will get used by the counting + * semaphore. xSemaphoreCreateCountingStatic() therefore allows a counting + * semaphore to be created without using any dynamic memory allocation. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ SemaphoreHandle_t xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + #define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) +#endif + +/** + * semphr. h + *
SemaphoreHandle_t xSemaphoreCreateCountingStatic( UBaseType_t uxMaxCount, UBaseType_t uxInitialCount, StaticSemaphore_t *pxSemaphoreBuffer )
+ * + * Creates a new counting semaphore instance, and returns a handle by which the + * new counting semaphore can be referenced. + * + * In many usage scenarios it is faster and more memory efficient to use a + * direct to task notification in place of a counting semaphore! + * http://www.freertos.org/RTOS-task-notifications.html + * + * Internally, within the FreeRTOS implementation, counting semaphores use a + * block of memory, in which the counting semaphore structure is stored. If a + * counting semaphore is created using xSemaphoreCreateCounting() then the + * required memory is automatically dynamically allocated inside the + * xSemaphoreCreateCounting() function. (see + * http://www.freertos.org/a00111.html). If a counting semaphore is created + * using xSemaphoreCreateCountingStatic() then the application writer must + * provide the memory. xSemaphoreCreateCountingStatic() therefore allows a + * counting semaphore to be created without using any dynamic memory allocation. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @param pxSemaphoreBuffer Must point to a variable of type StaticSemaphore_t, + * which will then be used to hold the semaphore's data structure, removing the + * need for the memory to be allocated dynamically. + * + * @return If the counting semaphore was successfully created then a handle to + * the created counting semaphore is returned. If pxSemaphoreBuffer was NULL + * then NULL is returned. + * + * Example usage: +
+ SemaphoreHandle_t xSemaphore;
+ StaticSemaphore_t xSemaphoreBuffer;
+
+ void vATask( void * pvParameters )
+ {
+ SemaphoreHandle_t xSemaphore = NULL;
+
+    // Counting semaphore cannot be used before they have been created.  Create
+    // a counting semaphore using xSemaphoreCreateCountingStatic().  The max
+    // value to which the semaphore can count is 10, and the initial value
+    // assigned to the count will be 0.  The address of xSemaphoreBuffer is
+    // passed in and will be used to hold the semaphore structure, so no dynamic
+    // memory allocation will be used.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0, &xSemaphoreBuffer );
+
+    // No memory allocation was attempted so xSemaphore cannot be NULL, so there
+    // is no need to check its value.
+ }
+ 
+ * \defgroup xSemaphoreCreateCountingStatic xSemaphoreCreateCountingStatic + * \ingroup Semaphores + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + #define xSemaphoreCreateCountingStatic( uxMaxCount, uxInitialCount, pxSemaphoreBuffer ) xQueueCreateCountingSemaphoreStatic( ( uxMaxCount ), ( uxInitialCount ), ( pxSemaphoreBuffer ) ) +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * semphr. h + *
void vSemaphoreDelete( SemaphoreHandle_t xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \defgroup vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( QueueHandle_t ) ( xSemaphore ) ) + +/** + * semphr.h + *
TaskHandle_t xSemaphoreGetMutexHolder( SemaphoreHandle_t xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + * Note: This is a good way of determining if the calling task is the mutex + * holder, but not a good way of determining the identity of the mutex holder as + * the holder may change between the function exiting and the returned value + * being tested. + */ +#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) + +/** + * semphr.h + *
TaskHandle_t xSemaphoreGetMutexHolderFromISR( SemaphoreHandle_t xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + */ +#define xSemaphoreGetMutexHolderFromISR( xSemaphore ) xQueueGetMutexHolderFromISR( ( xSemaphore ) ) + +/** + * semphr.h + *
UBaseType_t uxSemaphoreGetCount( SemaphoreHandle_t xSemaphore );
+ * + * If the semaphore is a counting semaphore then uxSemaphoreGetCount() returns + * its current count value. If the semaphore is a binary semaphore then + * uxSemaphoreGetCount() returns 1 if the semaphore is available, and 0 if the + * semaphore is not available. + * + */ +#define uxSemaphoreGetCount( xSemaphore ) uxQueueMessagesWaiting( ( QueueHandle_t ) ( xSemaphore ) ) + +#endif /* SEMAPHORE_H */ + + diff --git a/lib/FreeRTOS-SAMD51/src/stack_macros.h b/lib/FreeRTOS-SAMD51/src/stack_macros.h new file mode 100644 index 0000000..18406bb --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/stack_macros.h @@ -0,0 +1,129 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ + const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ + \ + if( ( pulStack[ 0 ] != ulCheckValue ) || \ + ( pulStack[ 1 ] != ulCheckValue ) || \ + ( pulStack[ 2 ] != ulCheckValue ) || \ + ( pulStack[ 3 ] != ulCheckValue ) ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskCHECK_FOR_STACK_OVERFLOW() \ + { \ + int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ + static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +/* Remove stack overflow macro if not being used. */ +#ifndef taskCHECK_FOR_STACK_OVERFLOW + #define taskCHECK_FOR_STACK_OVERFLOW() +#endif + + + +#endif /* STACK_MACROS_H */ + diff --git a/lib/FreeRTOS-SAMD51/src/stdint.readme b/lib/FreeRTOS-SAMD51/src/stdint.readme new file mode 100644 index 0000000..4414c29 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/stdint.readme @@ -0,0 +1,27 @@ + +#ifndef FREERTOS_STDINT +#define FREERTOS_STDINT + +/******************************************************************************* + * THIS IS NOT A FULL stdint.h IMPLEMENTATION - It only contains the definitions + * necessary to build the FreeRTOS code. It is provided to allow FreeRTOS to be + * built using compilers that do not provide their own stdint.h definition. + * + * To use this file: + * + * 1) Copy this file into the directory that contains your FreeRTOSConfig.h + * header file, as that directory will already be in the compilers include + * path. + * + * 2) Rename the copied file stdint.h. + * + */ + +typedef signed char int8_t; +typedef unsigned char uint8_t; +typedef short int16_t; +typedef unsigned short uint16_t; +typedef long int32_t; +typedef unsigned long uint32_t; + +#endif /* FREERTOS_STDINT */ diff --git a/lib/FreeRTOS-SAMD51/src/stream_buffer.c b/lib/FreeRTOS-SAMD51/src/stream_buffer.c new file mode 100644 index 0000000..8551970 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/stream_buffer.c @@ -0,0 +1,1263 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* Standard includes. */ +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "stream_buffer.h" + +#if( configUSE_TASK_NOTIFICATIONS != 1 ) + #error configUSE_TASK_NOTIFICATIONS must be set to 1 to build stream_buffer.c +#endif + +/* Lint e961, e9021 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + +/* If the user has not provided application specific Rx notification macros, +or #defined the notification macros away, them provide default implementations +that uses task notifications. */ +/*lint -save -e9026 Function like macros allowed and needed here so they can be overidden. */ +#ifndef sbRECEIVE_COMPLETED + #define sbRECEIVE_COMPLETED( pxStreamBuffer ) \ + vTaskSuspendAll(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) \ + { \ + ( void ) xTaskNotify( ( pxStreamBuffer )->xTaskWaitingToSend, \ + ( uint32_t ) 0, \ + eNoAction ); \ + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; \ + } \ + } \ + ( void ) xTaskResumeAll(); +#endif /* sbRECEIVE_COMPLETED */ + +#ifndef sbRECEIVE_COMPLETED_FROM_ISR + #define sbRECEIVE_COMPLETED_FROM_ISR( pxStreamBuffer, \ + pxHigherPriorityTaskWoken ) \ + { \ + UBaseType_t uxSavedInterruptStatus; \ + \ + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) \ + { \ + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToSend, \ + ( uint32_t ) 0, \ + eNoAction, \ + pxHigherPriorityTaskWoken ); \ + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; \ + } \ + } \ + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); \ + } +#endif /* sbRECEIVE_COMPLETED_FROM_ISR */ + +/* If the user has not provided an application specific Tx notification macro, +or #defined the notification macro away, them provide a default implementation +that uses task notifications. */ +#ifndef sbSEND_COMPLETED + #define sbSEND_COMPLETED( pxStreamBuffer ) \ + vTaskSuspendAll(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) \ + { \ + ( void ) xTaskNotify( ( pxStreamBuffer )->xTaskWaitingToReceive, \ + ( uint32_t ) 0, \ + eNoAction ); \ + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; \ + } \ + } \ + ( void ) xTaskResumeAll(); +#endif /* sbSEND_COMPLETED */ + +#ifndef sbSEND_COMPLETE_FROM_ISR + #define sbSEND_COMPLETE_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ) \ + { \ + UBaseType_t uxSavedInterruptStatus; \ + \ + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); \ + { \ + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) \ + { \ + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToReceive, \ + ( uint32_t ) 0, \ + eNoAction, \ + pxHigherPriorityTaskWoken ); \ + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; \ + } \ + } \ + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); \ + } +#endif /* sbSEND_COMPLETE_FROM_ISR */ +/*lint -restore (9026) */ + +/* The number of bytes used to hold the length of a message in the buffer. */ +#define sbBYTES_TO_STORE_MESSAGE_LENGTH ( sizeof( configMESSAGE_BUFFER_LENGTH_TYPE ) ) + +/* Bits stored in the ucFlags field of the stream buffer. */ +#define sbFLAGS_IS_MESSAGE_BUFFER ( ( uint8_t ) 1 ) /* Set if the stream buffer was created as a message buffer, in which case it holds discrete messages rather than a stream. */ +#define sbFLAGS_IS_STATICALLY_ALLOCATED ( ( uint8_t ) 2 ) /* Set if the stream buffer was created using statically allocated memory. */ + +/*-----------------------------------------------------------*/ + +/* Structure that hold state information on the buffer. */ +typedef struct StreamBufferDef_t /*lint !e9058 Style convention uses tag. */ +{ + volatile size_t xTail; /* Index to the next item to read within the buffer. */ + volatile size_t xHead; /* Index to the next item to write within the buffer. */ + size_t xLength; /* The length of the buffer pointed to by pucBuffer. */ + size_t xTriggerLevelBytes; /* The number of bytes that must be in the stream buffer before a task that is waiting for data is unblocked. */ + volatile TaskHandle_t xTaskWaitingToReceive; /* Holds the handle of a task waiting for data, or NULL if no tasks are waiting. */ + volatile TaskHandle_t xTaskWaitingToSend; /* Holds the handle of a task waiting to send data to a message buffer that is full. */ + uint8_t *pucBuffer; /* Points to the buffer itself - that is - the RAM that stores the data passed through the buffer. */ + uint8_t ucFlags; + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxStreamBufferNumber; /* Used for tracing purposes. */ + #endif +} StreamBuffer_t; + +/* + * The number of bytes available to be read from the buffer. + */ +static size_t prvBytesInBuffer( const StreamBuffer_t * const pxStreamBuffer ) PRIVILEGED_FUNCTION; + +/* + * Add xCount bytes from pucData into the pxStreamBuffer message buffer. + * Returns the number of bytes written, which will either equal xCount in the + * success case, or 0 if there was not enough space in the buffer (in which case + * no data is written into the buffer). + */ +static size_t prvWriteBytesToBuffer( StreamBuffer_t * const pxStreamBuffer, const uint8_t *pucData, size_t xCount ) PRIVILEGED_FUNCTION; + +/* + * If the stream buffer is being used as a message buffer, then reads an entire + * message out of the buffer. If the stream buffer is being used as a stream + * buffer then read as many bytes as possible from the buffer. + * prvReadBytesFromBuffer() is called to actually extract the bytes from the + * buffer's data storage area. + */ +static size_t prvReadMessageFromBuffer( StreamBuffer_t *pxStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + size_t xBytesAvailable, + size_t xBytesToStoreMessageLength ) PRIVILEGED_FUNCTION; + +/* + * If the stream buffer is being used as a message buffer, then writes an entire + * message to the buffer. If the stream buffer is being used as a stream + * buffer then write as many bytes as possible to the buffer. + * prvWriteBytestoBuffer() is called to actually send the bytes to the buffer's + * data storage area. + */ +static size_t prvWriteMessageToBuffer( StreamBuffer_t * const pxStreamBuffer, + const void * pvTxData, + size_t xDataLengthBytes, + size_t xSpace, + size_t xRequiredSpace ) PRIVILEGED_FUNCTION; + +/* + * Read xMaxCount bytes from the pxStreamBuffer message buffer and write them + * to pucData. + */ +static size_t prvReadBytesFromBuffer( StreamBuffer_t *pxStreamBuffer, + uint8_t *pucData, + size_t xMaxCount, + size_t xBytesAvailable ) PRIVILEGED_FUNCTION; + +/* + * Called by both pxStreamBufferCreate() and pxStreamBufferCreateStatic() to + * initialise the members of the newly created stream buffer structure. + */ +static void prvInitialiseNewStreamBuffer( StreamBuffer_t * const pxStreamBuffer, + uint8_t * const pucBuffer, + size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + uint8_t ucFlags ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + StreamBufferHandle_t xStreamBufferGenericCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes, BaseType_t xIsMessageBuffer ) + { + uint8_t *pucAllocatedMemory; + uint8_t ucFlags; + + /* In case the stream buffer is going to be used as a message buffer + (that is, it will hold discrete messages with a little meta data that + says how big the next message is) check the buffer will be large enough + to hold at least one message. */ + if( xIsMessageBuffer == pdTRUE ) + { + /* Is a message buffer but not statically allocated. */ + ucFlags = sbFLAGS_IS_MESSAGE_BUFFER; + configASSERT( xBufferSizeBytes > sbBYTES_TO_STORE_MESSAGE_LENGTH ); + } + else + { + /* Not a message buffer and not statically allocated. */ + ucFlags = 0; + configASSERT( xBufferSizeBytes > 0 ); + } + configASSERT( xTriggerLevelBytes <= xBufferSizeBytes ); + + /* A trigger level of 0 would cause a waiting task to unblock even when + the buffer was empty. */ + if( xTriggerLevelBytes == ( size_t ) 0 ) + { + xTriggerLevelBytes = ( size_t ) 1; + } + + /* A stream buffer requires a StreamBuffer_t structure and a buffer. + Both are allocated in a single call to pvPortMalloc(). The + StreamBuffer_t structure is placed at the start of the allocated memory + and the buffer follows immediately after. The requested size is + incremented so the free space is returned as the user would expect - + this is a quirk of the implementation that means otherwise the free + space would be reported as one byte smaller than would be logically + expected. */ + xBufferSizeBytes++; + pucAllocatedMemory = ( uint8_t * ) pvPortMalloc( xBufferSizeBytes + sizeof( StreamBuffer_t ) ); /*lint !e9079 malloc() only returns void*. */ + + if( pucAllocatedMemory != NULL ) + { + prvInitialiseNewStreamBuffer( ( StreamBuffer_t * ) pucAllocatedMemory, /* Structure at the start of the allocated memory. */ /*lint !e9087 Safe cast as allocated memory is aligned. */ /*lint !e826 Area is not too small and alignment is guaranteed provided malloc() behaves as expected and returns aligned buffer. */ + pucAllocatedMemory + sizeof( StreamBuffer_t ), /* Storage area follows. */ /*lint !e9016 Indexing past structure valid for uint8_t pointer, also storage area has no alignment requirement. */ + xBufferSizeBytes, + xTriggerLevelBytes, + ucFlags ); + + traceSTREAM_BUFFER_CREATE( ( ( StreamBuffer_t * ) pucAllocatedMemory ), xIsMessageBuffer ); + } + else + { + traceSTREAM_BUFFER_CREATE_FAILED( xIsMessageBuffer ); + } + + return ( StreamBufferHandle_t ) pucAllocatedMemory; /*lint !e9087 !e826 Safe cast as allocated memory is aligned. */ + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + StreamBufferHandle_t xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer, + uint8_t * const pucStreamBufferStorageArea, + StaticStreamBuffer_t * const pxStaticStreamBuffer ) + { + StreamBuffer_t * const pxStreamBuffer = ( StreamBuffer_t * ) pxStaticStreamBuffer; /*lint !e740 !e9087 Safe cast as StaticStreamBuffer_t is opaque Streambuffer_t. */ + StreamBufferHandle_t xReturn; + uint8_t ucFlags; + + configASSERT( pucStreamBufferStorageArea ); + configASSERT( pxStaticStreamBuffer ); + configASSERT( xTriggerLevelBytes <= xBufferSizeBytes ); + + /* A trigger level of 0 would cause a waiting task to unblock even when + the buffer was empty. */ + if( xTriggerLevelBytes == ( size_t ) 0 ) + { + xTriggerLevelBytes = ( size_t ) 1; + } + + if( xIsMessageBuffer != pdFALSE ) + { + /* Statically allocated message buffer. */ + ucFlags = sbFLAGS_IS_MESSAGE_BUFFER | sbFLAGS_IS_STATICALLY_ALLOCATED; + } + else + { + /* Statically allocated stream buffer. */ + ucFlags = sbFLAGS_IS_STATICALLY_ALLOCATED; + } + + /* In case the stream buffer is going to be used as a message buffer + (that is, it will hold discrete messages with a little meta data that + says how big the next message is) check the buffer will be large enough + to hold at least one message. */ + configASSERT( xBufferSizeBytes > sbBYTES_TO_STORE_MESSAGE_LENGTH ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticStreamBuffer_t equals the size of the real + message buffer structure. */ + volatile size_t xSize = sizeof( StaticStreamBuffer_t ); + configASSERT( xSize == sizeof( StreamBuffer_t ) ); + } /*lint !e529 xSize is referenced is configASSERT() is defined. */ + #endif /* configASSERT_DEFINED */ + + if( ( pucStreamBufferStorageArea != NULL ) && ( pxStaticStreamBuffer != NULL ) ) + { + prvInitialiseNewStreamBuffer( pxStreamBuffer, + pucStreamBufferStorageArea, + xBufferSizeBytes, + xTriggerLevelBytes, + ucFlags ); + + /* Remember this was statically allocated in case it is ever deleted + again. */ + pxStreamBuffer->ucFlags |= sbFLAGS_IS_STATICALLY_ALLOCATED; + + traceSTREAM_BUFFER_CREATE( pxStreamBuffer, xIsMessageBuffer ); + + xReturn = ( StreamBufferHandle_t ) pxStaticStreamBuffer; /*lint !e9087 Data hiding requires cast to opaque type. */ + } + else + { + xReturn = NULL; + traceSTREAM_BUFFER_CREATE_STATIC_FAILED( xReturn, xIsMessageBuffer ); + } + + return xReturn; + } + +#endif /* ( configSUPPORT_STATIC_ALLOCATION == 1 ) */ +/*-----------------------------------------------------------*/ + +void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * pxStreamBuffer = xStreamBuffer; + + configASSERT( pxStreamBuffer ); + + traceSTREAM_BUFFER_DELETE( xStreamBuffer ); + + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_STATICALLY_ALLOCATED ) == ( uint8_t ) pdFALSE ) + { + #if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* Both the structure and the buffer were allocated using a single call + to pvPortMalloc(), hence only one call to vPortFree() is required. */ + vPortFree( ( void * ) pxStreamBuffer ); /*lint !e9087 Standard free() semantics require void *, plus pxStreamBuffer was allocated by pvPortMalloc(). */ + } + #else + { + /* Should not be possible to get here, ucFlags must be corrupt. + Force an assert. */ + configASSERT( xStreamBuffer == ( StreamBufferHandle_t ) ~0 ); + } + #endif + } + else + { + /* The structure and buffer were not allocated dynamically and cannot be + freed - just scrub the structure so future use will assert. */ + ( void ) memset( pxStreamBuffer, 0x00, sizeof( StreamBuffer_t ) ); + } +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn = pdFAIL; + +#if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxStreamBufferNumber; +#endif + + configASSERT( pxStreamBuffer ); + + #if( configUSE_TRACE_FACILITY == 1 ) + { + /* Store the stream buffer number so it can be restored after the + reset. */ + uxStreamBufferNumber = pxStreamBuffer->uxStreamBufferNumber; + } + #endif + + /* Can only reset a message buffer if there are no tasks blocked on it. */ + taskENTER_CRITICAL(); + { + if( pxStreamBuffer->xTaskWaitingToReceive == NULL ) + { + if( pxStreamBuffer->xTaskWaitingToSend == NULL ) + { + prvInitialiseNewStreamBuffer( pxStreamBuffer, + pxStreamBuffer->pucBuffer, + pxStreamBuffer->xLength, + pxStreamBuffer->xTriggerLevelBytes, + pxStreamBuffer->ucFlags ); + xReturn = pdPASS; + + #if( configUSE_TRACE_FACILITY == 1 ) + { + pxStreamBuffer->uxStreamBufferNumber = uxStreamBufferNumber; + } + #endif + + traceSTREAM_BUFFER_RESET( xStreamBuffer ); + } + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; + + configASSERT( pxStreamBuffer ); + + /* It is not valid for the trigger level to be 0. */ + if( xTriggerLevel == ( size_t ) 0 ) + { + xTriggerLevel = ( size_t ) 1; + } + + /* The trigger level is the number of bytes that must be in the stream + buffer before a task that is waiting for data is unblocked. */ + if( xTriggerLevel <= pxStreamBuffer->xLength ) + { + pxStreamBuffer->xTriggerLevelBytes = xTriggerLevel; + xReturn = pdPASS; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xSpace; + + configASSERT( pxStreamBuffer ); + + xSpace = pxStreamBuffer->xLength + pxStreamBuffer->xTail; + xSpace -= pxStreamBuffer->xHead; + xSpace -= ( size_t ) 1; + + if( xSpace >= pxStreamBuffer->xLength ) + { + xSpace -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xSpace; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn; + + configASSERT( pxStreamBuffer ); + + xReturn = prvBytesInBuffer( pxStreamBuffer ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + TickType_t xTicksToWait ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xSpace = 0; +size_t xRequiredSpace = xDataLengthBytes; +TimeOut_t xTimeOut; + + configASSERT( pvTxData ); + configASSERT( pxStreamBuffer ); + + /* This send function is used to write to both message buffers and stream + buffers. If this is a message buffer then the space needed must be + increased by the amount of bytes needed to store the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xRequiredSpace += sbBYTES_TO_STORE_MESSAGE_LENGTH; + + /* Overflow? */ + configASSERT( xRequiredSpace > xDataLengthBytes ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xTicksToWait != ( TickType_t ) 0 ) + { + vTaskSetTimeOutState( &xTimeOut ); + + do + { + /* Wait until the required number of bytes are free in the message + buffer. */ + taskENTER_CRITICAL(); + { + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + + if( xSpace < xRequiredSpace ) + { + /* Clear notification state as going to wait for space. */ + ( void ) xTaskNotifyStateClear( NULL ); + + /* Should only be one writer. */ + configASSERT( pxStreamBuffer->xTaskWaitingToSend == NULL ); + pxStreamBuffer->xTaskWaitingToSend = xTaskGetCurrentTaskHandle(); + } + else + { + taskEXIT_CRITICAL(); + break; + } + } + taskEXIT_CRITICAL(); + + traceBLOCKING_ON_STREAM_BUFFER_SEND( xStreamBuffer ); + ( void ) xTaskNotifyWait( ( uint32_t ) 0, ( uint32_t ) 0, NULL, xTicksToWait ); + pxStreamBuffer->xTaskWaitingToSend = NULL; + + } while( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xSpace == ( size_t ) 0 ) + { + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xReturn = prvWriteMessageToBuffer( pxStreamBuffer, pvTxData, xDataLengthBytes, xSpace, xRequiredSpace ); + + if( xReturn > ( size_t ) 0 ) + { + traceSTREAM_BUFFER_SEND( xStreamBuffer, xReturn ); + + /* Was a task waiting for the data? */ + if( prvBytesInBuffer( pxStreamBuffer ) >= pxStreamBuffer->xTriggerLevelBytes ) + { + sbSEND_COMPLETED( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + traceSTREAM_BUFFER_SEND_FAILED( xStreamBuffer ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xSpace; +size_t xRequiredSpace = xDataLengthBytes; + + configASSERT( pvTxData ); + configASSERT( pxStreamBuffer ); + + /* This send function is used to write to both message buffers and stream + buffers. If this is a message buffer then the space needed must be + increased by the amount of bytes needed to store the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xRequiredSpace += sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xSpace = xStreamBufferSpacesAvailable( pxStreamBuffer ); + xReturn = prvWriteMessageToBuffer( pxStreamBuffer, pvTxData, xDataLengthBytes, xSpace, xRequiredSpace ); + + if( xReturn > ( size_t ) 0 ) + { + /* Was a task waiting for the data? */ + if( prvBytesInBuffer( pxStreamBuffer ) >= pxStreamBuffer->xTriggerLevelBytes ) + { + sbSEND_COMPLETE_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceSTREAM_BUFFER_SEND_FROM_ISR( xStreamBuffer, xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static size_t prvWriteMessageToBuffer( StreamBuffer_t * const pxStreamBuffer, + const void * pvTxData, + size_t xDataLengthBytes, + size_t xSpace, + size_t xRequiredSpace ) +{ + BaseType_t xShouldWrite; + size_t xReturn; + + if( xSpace == ( size_t ) 0 ) + { + /* Doesn't matter if this is a stream buffer or a message buffer, there + is no space to write. */ + xShouldWrite = pdFALSE; + } + else if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) == ( uint8_t ) 0 ) + { + /* This is a stream buffer, as opposed to a message buffer, so writing a + stream of bytes rather than discrete messages. Write as many bytes as + possible. */ + xShouldWrite = pdTRUE; + xDataLengthBytes = configMIN( xDataLengthBytes, xSpace ); + } + else if( xSpace >= xRequiredSpace ) + { + /* This is a message buffer, as opposed to a stream buffer, and there + is enough space to write both the message length and the message itself + into the buffer. Start by writing the length of the data, the data + itself will be written later in this function. */ + xShouldWrite = pdTRUE; + ( void ) prvWriteBytesToBuffer( pxStreamBuffer, ( const uint8_t * ) &( xDataLengthBytes ), sbBYTES_TO_STORE_MESSAGE_LENGTH ); + } + else + { + /* There is space available, but not enough space. */ + xShouldWrite = pdFALSE; + } + + if( xShouldWrite != pdFALSE ) + { + /* Writes the data itself. */ + xReturn = prvWriteBytesToBuffer( pxStreamBuffer, ( const uint8_t * ) pvTxData, xDataLengthBytes ); /*lint !e9079 Storage buffer is implemented as uint8_t for ease of sizing, alighment and access. */ + } + else + { + xReturn = 0; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + TickType_t xTicksToWait ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReceivedLength = 0, xBytesAvailable, xBytesToStoreMessageLength; + + configASSERT( pvRxData ); + configASSERT( pxStreamBuffer ); + + /* This receive function is used by both message buffers, which store + discrete messages, and stream buffers, which store a continuous stream of + bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + if( xTicksToWait != ( TickType_t ) 0 ) + { + /* Checking if there is data and clearing the notification state must be + performed atomically. */ + taskENTER_CRITICAL(); + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + + /* If this function was invoked by a message buffer read then + xBytesToStoreMessageLength holds the number of bytes used to hold + the length of the next discrete message. If this function was + invoked by a stream buffer read then xBytesToStoreMessageLength will + be 0. */ + if( xBytesAvailable <= xBytesToStoreMessageLength ) + { + /* Clear notification state as going to wait for data. */ + ( void ) xTaskNotifyStateClear( NULL ); + + /* Should only be one reader. */ + configASSERT( pxStreamBuffer->xTaskWaitingToReceive == NULL ); + pxStreamBuffer->xTaskWaitingToReceive = xTaskGetCurrentTaskHandle(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + if( xBytesAvailable <= xBytesToStoreMessageLength ) + { + /* Wait for data to be available. */ + traceBLOCKING_ON_STREAM_BUFFER_RECEIVE( xStreamBuffer ); + ( void ) xTaskNotifyWait( ( uint32_t ) 0, ( uint32_t ) 0, NULL, xTicksToWait ); + pxStreamBuffer->xTaskWaitingToReceive = NULL; + + /* Recheck the data available after blocking. */ + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + } + + /* Whether receiving a discrete message (where xBytesToStoreMessageLength + holds the number of bytes used to store the message length) or a stream of + bytes (where xBytesToStoreMessageLength is zero), the number of bytes + available must be greater than xBytesToStoreMessageLength to be able to + read bytes from the buffer. */ + if( xBytesAvailable > xBytesToStoreMessageLength ) + { + xReceivedLength = prvReadMessageFromBuffer( pxStreamBuffer, pvRxData, xBufferLengthBytes, xBytesAvailable, xBytesToStoreMessageLength ); + + /* Was a task waiting for space in the buffer? */ + if( xReceivedLength != ( size_t ) 0 ) + { + traceSTREAM_BUFFER_RECEIVE( xStreamBuffer, xReceivedLength ); + sbRECEIVE_COMPLETED( pxStreamBuffer ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + traceSTREAM_BUFFER_RECEIVE_FAILED( xStreamBuffer ); + mtCOVERAGE_TEST_MARKER(); + } + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReturn, xBytesAvailable, xOriginalTail; +configMESSAGE_BUFFER_LENGTH_TYPE xTempReturn; + + configASSERT( pxStreamBuffer ); + + /* Ensure the stream buffer is being used as a message buffer. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + if( xBytesAvailable > sbBYTES_TO_STORE_MESSAGE_LENGTH ) + { + /* The number of bytes available is greater than the number of bytes + required to hold the length of the next message, so another message + is available. Return its length without removing the length bytes + from the buffer. A copy of the tail is stored so the buffer can be + returned to its prior state as the message is not actually being + removed from the buffer. */ + xOriginalTail = pxStreamBuffer->xTail; + ( void ) prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) &xTempReturn, sbBYTES_TO_STORE_MESSAGE_LENGTH, xBytesAvailable ); + xReturn = ( size_t ) xTempReturn; + pxStreamBuffer->xTail = xOriginalTail; + } + else + { + /* The minimum amount of bytes in a message buffer is + ( sbBYTES_TO_STORE_MESSAGE_LENGTH + 1 ), so if xBytesAvailable is + less than sbBYTES_TO_STORE_MESSAGE_LENGTH the only other valid + value is 0. */ + configASSERT( xBytesAvailable == 0 ); + xReturn = 0; + } + } + else + { + xReturn = 0; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +size_t xReceivedLength = 0, xBytesAvailable, xBytesToStoreMessageLength; + + configASSERT( pvRxData ); + configASSERT( pxStreamBuffer ); + + /* This receive function is used by both message buffers, which store + discrete messages, and stream buffers, which store a continuous stream of + bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the + message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + xBytesAvailable = prvBytesInBuffer( pxStreamBuffer ); + + /* Whether receiving a discrete message (where xBytesToStoreMessageLength + holds the number of bytes used to store the message length) or a stream of + bytes (where xBytesToStoreMessageLength is zero), the number of bytes + available must be greater than xBytesToStoreMessageLength to be able to + read bytes from the buffer. */ + if( xBytesAvailable > xBytesToStoreMessageLength ) + { + xReceivedLength = prvReadMessageFromBuffer( pxStreamBuffer, pvRxData, xBufferLengthBytes, xBytesAvailable, xBytesToStoreMessageLength ); + + /* Was a task waiting for space in the buffer? */ + if( xReceivedLength != ( size_t ) 0 ) + { + sbRECEIVE_COMPLETED_FROM_ISR( pxStreamBuffer, pxHigherPriorityTaskWoken ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceSTREAM_BUFFER_RECEIVE_FROM_ISR( xStreamBuffer, xReceivedLength ); + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +static size_t prvReadMessageFromBuffer( StreamBuffer_t *pxStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + size_t xBytesAvailable, + size_t xBytesToStoreMessageLength ) +{ +size_t xOriginalTail, xReceivedLength, xNextMessageLength; +configMESSAGE_BUFFER_LENGTH_TYPE xTempNextMessageLength; + + if( xBytesToStoreMessageLength != ( size_t ) 0 ) + { + /* A discrete message is being received. First receive the length + of the message. A copy of the tail is stored so the buffer can be + returned to its prior state if the length of the message is too + large for the provided buffer. */ + xOriginalTail = pxStreamBuffer->xTail; + ( void ) prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) &xTempNextMessageLength, xBytesToStoreMessageLength, xBytesAvailable ); + xNextMessageLength = ( size_t ) xTempNextMessageLength; + + /* Reduce the number of bytes available by the number of bytes just + read out. */ + xBytesAvailable -= xBytesToStoreMessageLength; + + /* Check there is enough space in the buffer provided by the + user. */ + if( xNextMessageLength > xBufferLengthBytes ) + { + /* The user has provided insufficient space to read the message + so return the buffer to its previous state (so the length of + the message is in the buffer again). */ + pxStreamBuffer->xTail = xOriginalTail; + xNextMessageLength = 0; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* A stream of bytes is being received (as opposed to a discrete + message), so read as many bytes as possible. */ + xNextMessageLength = xBufferLengthBytes; + } + + /* Read the actual data. */ + xReceivedLength = prvReadBytesFromBuffer( pxStreamBuffer, ( uint8_t * ) pvRxData, xNextMessageLength, xBytesAvailable ); /*lint !e9079 Data storage area is implemented as uint8_t array for ease of sizing, indexing and alignment. */ + + return xReceivedLength; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) +{ +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +size_t xTail; + + configASSERT( pxStreamBuffer ); + + /* True if no bytes are available. */ + xTail = pxStreamBuffer->xTail; + if( pxStreamBuffer->xHead == xTail ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) +{ +BaseType_t xReturn; +size_t xBytesToStoreMessageLength; +const StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; + + configASSERT( pxStreamBuffer ); + + /* This generic version of the receive function is used by both message + buffers, which store discrete messages, and stream buffers, which store a + continuous stream of bytes. Discrete messages include an additional + sbBYTES_TO_STORE_MESSAGE_LENGTH bytes that hold the length of the message. */ + if( ( pxStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ) != ( uint8_t ) 0 ) + { + xBytesToStoreMessageLength = sbBYTES_TO_STORE_MESSAGE_LENGTH; + } + else + { + xBytesToStoreMessageLength = 0; + } + + /* True if the available space equals zero. */ + if( xStreamBufferSpacesAvailable( xStreamBuffer ) <= xBytesToStoreMessageLength ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + configASSERT( pxStreamBuffer ); + + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxStreamBuffer )->xTaskWaitingToReceive != NULL ) + { + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToReceive, + ( uint32_t ) 0, + eNoAction, + pxHigherPriorityTaskWoken ); + ( pxStreamBuffer )->xTaskWaitingToReceive = NULL; + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) +{ +StreamBuffer_t * const pxStreamBuffer = xStreamBuffer; +BaseType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + configASSERT( pxStreamBuffer ); + + uxSavedInterruptStatus = ( UBaseType_t ) portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( ( pxStreamBuffer )->xTaskWaitingToSend != NULL ) + { + ( void ) xTaskNotifyFromISR( ( pxStreamBuffer )->xTaskWaitingToSend, + ( uint32_t ) 0, + eNoAction, + pxHigherPriorityTaskWoken ); + ( pxStreamBuffer )->xTaskWaitingToSend = NULL; + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static size_t prvWriteBytesToBuffer( StreamBuffer_t * const pxStreamBuffer, const uint8_t *pucData, size_t xCount ) +{ +size_t xNextHead, xFirstLength; + + configASSERT( xCount > ( size_t ) 0 ); + + xNextHead = pxStreamBuffer->xHead; + + /* Calculate the number of bytes that can be added in the first write - + which may be less than the total number of bytes that need to be added if + the buffer will wrap back to the beginning. */ + xFirstLength = configMIN( pxStreamBuffer->xLength - xNextHead, xCount ); + + /* Write as many bytes as can be written in the first write. */ + configASSERT( ( xNextHead + xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void* ) ( &( pxStreamBuffer->pucBuffer[ xNextHead ] ) ), ( const void * ) pucData, xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + + /* If the number of bytes written was less than the number that could be + written in the first write... */ + if( xCount > xFirstLength ) + { + /* ...then write the remaining bytes to the start of the buffer. */ + configASSERT( ( xCount - xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void * ) pxStreamBuffer->pucBuffer, ( const void * ) &( pucData[ xFirstLength ] ), xCount - xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + xNextHead += xCount; + if( xNextHead >= pxStreamBuffer->xLength ) + { + xNextHead -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxStreamBuffer->xHead = xNextHead; + + return xCount; +} +/*-----------------------------------------------------------*/ + +static size_t prvReadBytesFromBuffer( StreamBuffer_t *pxStreamBuffer, uint8_t *pucData, size_t xMaxCount, size_t xBytesAvailable ) +{ +size_t xCount, xFirstLength, xNextTail; + + /* Use the minimum of the wanted bytes and the available bytes. */ + xCount = configMIN( xBytesAvailable, xMaxCount ); + + if( xCount > ( size_t ) 0 ) + { + xNextTail = pxStreamBuffer->xTail; + + /* Calculate the number of bytes that can be read - which may be + less than the number wanted if the data wraps around to the start of + the buffer. */ + xFirstLength = configMIN( pxStreamBuffer->xLength - xNextTail, xCount ); + + /* Obtain the number of bytes it is possible to obtain in the first + read. Asserts check bounds of read and write. */ + configASSERT( xFirstLength <= xMaxCount ); + configASSERT( ( xNextTail + xFirstLength ) <= pxStreamBuffer->xLength ); + ( void ) memcpy( ( void * ) pucData, ( const void * ) &( pxStreamBuffer->pucBuffer[ xNextTail ] ), xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + + /* If the total number of wanted bytes is greater than the number + that could be read in the first read... */ + if( xCount > xFirstLength ) + { + /*...then read the remaining bytes from the start of the buffer. */ + configASSERT( xCount <= xMaxCount ); + ( void ) memcpy( ( void * ) &( pucData[ xFirstLength ] ), ( void * ) ( pxStreamBuffer->pucBuffer ), xCount - xFirstLength ); /*lint !e9087 memcpy() requires void *. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Move the tail pointer to effectively remove the data read from + the buffer. */ + xNextTail += xCount; + + if( xNextTail >= pxStreamBuffer->xLength ) + { + xNextTail -= pxStreamBuffer->xLength; + } + + pxStreamBuffer->xTail = xNextTail; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCount; +} +/*-----------------------------------------------------------*/ + +static size_t prvBytesInBuffer( const StreamBuffer_t * const pxStreamBuffer ) +{ +/* Returns the distance between xTail and xHead. */ +size_t xCount; + + xCount = pxStreamBuffer->xLength + pxStreamBuffer->xHead; + xCount -= pxStreamBuffer->xTail; + if ( xCount >= pxStreamBuffer->xLength ) + { + xCount -= pxStreamBuffer->xLength; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xCount; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewStreamBuffer( StreamBuffer_t * const pxStreamBuffer, + uint8_t * const pucBuffer, + size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + uint8_t ucFlags ) +{ + /* Assert here is deliberately writing to the entire buffer to ensure it can + be written to without generating exceptions, and is setting the buffer to a + known value to assist in development/debugging. */ + #if( configASSERT_DEFINED == 1 ) + { + /* The value written just has to be identifiable when looking at the + memory. Don't use 0xA5 as that is the stack fill value and could + result in confusion as to what is actually being observed. */ + const BaseType_t xWriteValue = 0x55; + configASSERT( memset( pucBuffer, ( int ) xWriteValue, xBufferSizeBytes ) == pucBuffer ); + } /*lint !e529 !e438 xWriteValue is only used if configASSERT() is defined. */ + #endif + + ( void ) memset( ( void * ) pxStreamBuffer, 0x00, sizeof( StreamBuffer_t ) ); /*lint !e9087 memset() requires void *. */ + pxStreamBuffer->pucBuffer = pucBuffer; + pxStreamBuffer->xLength = xBufferSizeBytes; + pxStreamBuffer->xTriggerLevelBytes = xTriggerLevelBytes; + pxStreamBuffer->ucFlags = ucFlags; +} + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxStreamBufferGetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer ) + { + return xStreamBuffer->uxStreamBufferNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vStreamBufferSetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer, UBaseType_t uxStreamBufferNumber ) + { + xStreamBuffer->uxStreamBufferNumber = uxStreamBufferNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + uint8_t ucStreamBufferGetStreamBufferType( StreamBufferHandle_t xStreamBuffer ) + { + return ( xStreamBuffer->ucFlags & sbFLAGS_IS_MESSAGE_BUFFER ); + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ diff --git a/lib/FreeRTOS-SAMD51/src/stream_buffer.h b/lib/FreeRTOS-SAMD51/src/stream_buffer.h new file mode 100644 index 0000000..0f00119 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/stream_buffer.h @@ -0,0 +1,855 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* + * Stream buffers are used to send a continuous stream of data from one task or + * interrupt to another. Their implementation is light weight, making them + * particularly suited for interrupt to task and core to core communication + * scenarios. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferRead()) inside a critical section section and set the + * receive block time to 0. + * + */ + +#ifndef STREAM_BUFFER_H +#define STREAM_BUFFER_H + +#if defined( __cplusplus ) +extern "C" { +#endif + +/** + * Type by which stream buffers are referenced. For example, a call to + * xStreamBufferCreate() returns an StreamBufferHandle_t variable that can + * then be used as a parameter to xStreamBufferSend(), xStreamBufferReceive(), + * etc. + */ +struct StreamBufferDef_t; +typedef struct StreamBufferDef_t * StreamBufferHandle_t; + + +/** + * message_buffer.h + * +
+StreamBufferHandle_t xStreamBufferCreate( size_t xBufferSizeBytes, size_t xTriggerLevelBytes );
+
+ * + * Creates a new stream buffer using dynamically allocated memory. See + * xStreamBufferCreateStatic() for a version that uses statically allocated + * memory (memory that is allocated at compile time). + * + * configSUPPORT_DYNAMIC_ALLOCATION must be set to 1 or left undefined in + * FreeRTOSConfig.h for xStreamBufferCreate() to be available. + * + * @param xBufferSizeBytes The total number of bytes the stream buffer will be + * able to hold at any one time. + * + * @param xTriggerLevelBytes The number of bytes that must be in the stream + * buffer before a task that is blocked on the stream buffer to wait for data is + * moved out of the blocked state. For example, if a task is blocked on a read + * of an empty stream buffer that has a trigger level of 1 then the task will be + * unblocked when a single byte is written to the buffer or the task's block + * time expires. As another example, if a task is blocked on a read of an empty + * stream buffer that has a trigger level of 10 then the task will not be + * unblocked until the stream buffer contains at least 10 bytes or the task's + * block time expires. If a reading task's block time expires before the + * trigger level is reached then the task will still receive however many bytes + * are actually available. Setting a trigger level of 0 will result in a + * trigger level of 1 being used. It is not valid to specify a trigger level + * that is greater than the buffer size. + * + * @return If NULL is returned, then the stream buffer cannot be created + * because there is insufficient heap memory available for FreeRTOS to allocate + * the stream buffer data structures and storage area. A non-NULL value being + * returned indicates that the stream buffer has been created successfully - + * the returned value should be stored as the handle to the created stream + * buffer. + * + * Example use: +
+
+void vAFunction( void )
+{
+StreamBufferHandle_t xStreamBuffer;
+const size_t xStreamBufferSizeBytes = 100, xTriggerLevel = 10;
+
+    // Create a stream buffer that can hold 100 bytes.  The memory used to hold
+    // both the stream buffer structure and the data in the stream buffer is
+    // allocated dynamically.
+    xStreamBuffer = xStreamBufferCreate( xStreamBufferSizeBytes, xTriggerLevel );
+
+    if( xStreamBuffer == NULL )
+    {
+        // There was not enough heap memory space available to create the
+        // stream buffer.
+    }
+    else
+    {
+        // The stream buffer was created successfully and can now be used.
+    }
+}
+
+ * \defgroup xStreamBufferCreate xStreamBufferCreate + * \ingroup StreamBufferManagement + */ +#define xStreamBufferCreate( xBufferSizeBytes, xTriggerLevelBytes ) xStreamBufferGenericCreate( xBufferSizeBytes, xTriggerLevelBytes, pdFALSE ) + +/** + * stream_buffer.h + * +
+StreamBufferHandle_t xStreamBufferCreateStatic( size_t xBufferSizeBytes,
+                                                size_t xTriggerLevelBytes,
+                                                uint8_t *pucStreamBufferStorageArea,
+                                                StaticStreamBuffer_t *pxStaticStreamBuffer );
+
+ * Creates a new stream buffer using statically allocated memory. See + * xStreamBufferCreate() for a version that uses dynamically allocated memory. + * + * configSUPPORT_STATIC_ALLOCATION must be set to 1 in FreeRTOSConfig.h for + * xStreamBufferCreateStatic() to be available. + * + * @param xBufferSizeBytes The size, in bytes, of the buffer pointed to by the + * pucStreamBufferStorageArea parameter. + * + * @param xTriggerLevelBytes The number of bytes that must be in the stream + * buffer before a task that is blocked on the stream buffer to wait for data is + * moved out of the blocked state. For example, if a task is blocked on a read + * of an empty stream buffer that has a trigger level of 1 then the task will be + * unblocked when a single byte is written to the buffer or the task's block + * time expires. As another example, if a task is blocked on a read of an empty + * stream buffer that has a trigger level of 10 then the task will not be + * unblocked until the stream buffer contains at least 10 bytes or the task's + * block time expires. If a reading task's block time expires before the + * trigger level is reached then the task will still receive however many bytes + * are actually available. Setting a trigger level of 0 will result in a + * trigger level of 1 being used. It is not valid to specify a trigger level + * that is greater than the buffer size. + * + * @param pucStreamBufferStorageArea Must point to a uint8_t array that is at + * least xBufferSizeBytes + 1 big. This is the array to which streams are + * copied when they are written to the stream buffer. + * + * @param pxStaticStreamBuffer Must point to a variable of type + * StaticStreamBuffer_t, which will be used to hold the stream buffer's data + * structure. + * + * @return If the stream buffer is created successfully then a handle to the + * created stream buffer is returned. If either pucStreamBufferStorageArea or + * pxStaticstreamBuffer are NULL then NULL is returned. + * + * Example use: +
+
+// Used to dimension the array used to hold the streams.  The available space
+// will actually be one less than this, so 999.
+#define STORAGE_SIZE_BYTES 1000
+
+// Defines the memory that will actually hold the streams within the stream
+// buffer.
+static uint8_t ucStorageBuffer[ STORAGE_SIZE_BYTES ];
+
+// The variable used to hold the stream buffer structure.
+StaticStreamBuffer_t xStreamBufferStruct;
+
+void MyFunction( void )
+{
+StreamBufferHandle_t xStreamBuffer;
+const size_t xTriggerLevel = 1;
+
+    xStreamBuffer = xStreamBufferCreateStatic( sizeof( ucBufferStorage ),
+                                               xTriggerLevel,
+                                               ucBufferStorage,
+                                               &xStreamBufferStruct );
+
+    // As neither the pucStreamBufferStorageArea or pxStaticStreamBuffer
+    // parameters were NULL, xStreamBuffer will not be NULL, and can be used to
+    // reference the created stream buffer in other stream buffer API calls.
+
+    // Other code that uses the stream buffer can go here.
+}
+
+
+ * \defgroup xStreamBufferCreateStatic xStreamBufferCreateStatic + * \ingroup StreamBufferManagement + */ +#define xStreamBufferCreateStatic( xBufferSizeBytes, xTriggerLevelBytes, pucStreamBufferStorageArea, pxStaticStreamBuffer ) xStreamBufferGenericCreateStatic( xBufferSizeBytes, xTriggerLevelBytes, pdFALSE, pucStreamBufferStorageArea, pxStaticStreamBuffer ) + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer,
+                          const void *pvTxData,
+                          size_t xDataLengthBytes,
+                          TickType_t xTicksToWait );
+
+ * + * Sends bytes to a stream buffer. The bytes are copied into the stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferSend() to write to a stream buffer from a task. Use + * xStreamBufferSendFromISR() to write to a stream buffer from an interrupt + * service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer to which a stream is + * being sent. + * + * @param pvTxData A pointer to the buffer that holds the bytes to be copied + * into the stream buffer. + * + * @param xDataLengthBytes The maximum number of bytes to copy from pvTxData + * into the stream buffer. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for enough space to become available in the stream + * buffer, should the stream buffer contain too little space to hold the + * another xDataLengthBytes bytes. The block time is specified in tick periods, + * so the absolute time it represents is dependent on the tick frequency. The + * macro pdMS_TO_TICKS() can be used to convert a time specified in milliseconds + * into a time specified in ticks. Setting xTicksToWait to portMAX_DELAY will + * cause the task to wait indefinitely (without timing out), provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h. If a task times out + * before it can write all xDataLengthBytes into the buffer it will still write + * as many bytes as possible. A task does not use any CPU time when it is in + * the blocked state. + * + * @return The number of bytes written to the stream buffer. If a task times + * out before it can write all xDataLengthBytes into the buffer it will still + * write as many bytes as possible. + * + * Example use: +
+void vAFunction( StreamBufferHandle_t xStreamBuffer )
+{
+size_t xBytesSent;
+uint8_t ucArrayToSend[] = { 0, 1, 2, 3 };
+char *pcStringToSend = "String to send";
+const TickType_t x100ms = pdMS_TO_TICKS( 100 );
+
+    // Send an array to the stream buffer, blocking for a maximum of 100ms to
+    // wait for enough space to be available in the stream buffer.
+    xBytesSent = xStreamBufferSend( xStreamBuffer, ( void * ) ucArrayToSend, sizeof( ucArrayToSend ), x100ms );
+
+    if( xBytesSent != sizeof( ucArrayToSend ) )
+    {
+        // The call to xStreamBufferSend() times out before there was enough
+        // space in the buffer for the data to be written, but it did
+        // successfully write xBytesSent bytes.
+    }
+
+    // Send the string to the stream buffer.  Return immediately if there is not
+    // enough space in the buffer.
+    xBytesSent = xStreamBufferSend( xStreamBuffer, ( void * ) pcStringToSend, strlen( pcStringToSend ), 0 );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // The entire string could not be added to the stream buffer because
+        // there was not enough free space in the buffer, but xBytesSent bytes
+        // were sent.  Could try again to send the remaining bytes.
+    }
+}
+
+ * \defgroup xStreamBufferSend xStreamBufferSend + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSend( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer,
+                                 const void *pvTxData,
+                                 size_t xDataLengthBytes,
+                                 BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * Interrupt safe version of the API function that sends a stream of bytes to + * the stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferSend() to write to a stream buffer from a task. Use + * xStreamBufferSendFromISR() to write to a stream buffer from an interrupt + * service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer to which a stream is + * being sent. + * + * @param pvTxData A pointer to the data that is to be copied into the stream + * buffer. + * + * @param xDataLengthBytes The maximum number of bytes to copy from pvTxData + * into the stream buffer. + * + * @param pxHigherPriorityTaskWoken It is possible that a stream buffer will + * have a task blocked on it waiting for data. Calling + * xStreamBufferSendFromISR() can make data available, and so cause a task that + * was waiting for data to leave the Blocked state. If calling + * xStreamBufferSendFromISR() causes a task to leave the Blocked state, and the + * unblocked task has a priority higher than the currently executing task (the + * task that was interrupted), then, internally, xStreamBufferSendFromISR() + * will set *pxHigherPriorityTaskWoken to pdTRUE. If + * xStreamBufferSendFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. This will + * ensure that the interrupt returns directly to the highest priority Ready + * state task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it + * is passed into the function. See the example code below for an example. + * + * @return The number of bytes actually written to the stream buffer, which will + * be less than xDataLengthBytes if the stream buffer didn't have enough free + * space for all the bytes to be written. + * + * Example use: +
+// A stream buffer that has already been created.
+StreamBufferHandle_t xStreamBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+size_t xBytesSent;
+char *pcStringToSend = "String to send";
+BaseType_t xHigherPriorityTaskWoken = pdFALSE; // Initialised to pdFALSE.
+
+    // Attempt to send the string to the stream buffer.
+    xBytesSent = xStreamBufferSendFromISR( xStreamBuffer,
+                                           ( void * ) pcStringToSend,
+                                           strlen( pcStringToSend ),
+                                           &xHigherPriorityTaskWoken );
+
+    if( xBytesSent != strlen( pcStringToSend ) )
+    {
+        // There was not enough free space in the stream buffer for the entire
+        // string to be written, ut xBytesSent bytes were written.
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xStreamBufferSendFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xStreamBufferSendFromISR xStreamBufferSendFromISR + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSendFromISR( StreamBufferHandle_t xStreamBuffer, + const void *pvTxData, + size_t xDataLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer,
+                             void *pvRxData,
+                             size_t xBufferLengthBytes,
+                             TickType_t xTicksToWait );
+
+ * + * Receives bytes from a stream buffer. + * + * ***NOTE***: Uniquely among FreeRTOS objects, the stream buffer + * implementation (so also the message buffer implementation, as message buffers + * are built on top of stream buffers) assumes there is only one task or + * interrupt that will write to the buffer (the writer), and only one task or + * interrupt that will read from the buffer (the reader). It is safe for the + * writer and reader to be different tasks or interrupts, but, unlike other + * FreeRTOS objects, it is not safe to have multiple different writers or + * multiple different readers. If there are to be multiple different writers + * then the application writer must place each call to a writing API function + * (such as xStreamBufferSend()) inside a critical section and set the send + * block time to 0. Likewise, if there are to be multiple different readers + * then the application writer must place each call to a reading API function + * (such as xStreamBufferRead()) inside a critical section and set the receive + * block time to 0. + * + * Use xStreamBufferReceive() to read from a stream buffer from a task. Use + * xStreamBufferReceiveFromISR() to read from a stream buffer from an + * interrupt service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer from which bytes are to + * be received. + * + * @param pvRxData A pointer to the buffer into which the received bytes will be + * copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the + * pvRxData parameter. This sets the maximum number of bytes to receive in one + * call. xStreamBufferReceive will return as many bytes as possible up to a + * maximum set by xBufferLengthBytes. + * + * @param xTicksToWait The maximum amount of time the task should remain in the + * Blocked state to wait for data to become available if the stream buffer is + * empty. xStreamBufferReceive() will return immediately if xTicksToWait is + * zero. The block time is specified in tick periods, so the absolute time it + * represents is dependent on the tick frequency. The macro pdMS_TO_TICKS() can + * be used to convert a time specified in milliseconds into a time specified in + * ticks. Setting xTicksToWait to portMAX_DELAY will cause the task to wait + * indefinitely (without timing out), provided INCLUDE_vTaskSuspend is set to 1 + * in FreeRTOSConfig.h. A task does not use any CPU time when it is in the + * Blocked state. + * + * @return The number of bytes actually read from the stream buffer, which will + * be less than xBufferLengthBytes if the call to xStreamBufferReceive() timed + * out before xBufferLengthBytes were available. + * + * Example use: +
+void vAFunction( StreamBuffer_t xStreamBuffer )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+const TickType_t xBlockTime = pdMS_TO_TICKS( 20 );
+
+    // Receive up to another sizeof( ucRxData ) bytes from the stream buffer.
+    // Wait in the Blocked state (so not using any CPU processing time) for a
+    // maximum of 100ms for the full sizeof( ucRxData ) number of bytes to be
+    // available.
+    xReceivedBytes = xStreamBufferReceive( xStreamBuffer,
+                                           ( void * ) ucRxData,
+                                           sizeof( ucRxData ),
+                                           xBlockTime );
+
+    if( xReceivedBytes > 0 )
+    {
+        // A ucRxData contains another xRecievedBytes bytes of data, which can
+        // be processed here....
+    }
+}
+
+ * \defgroup xStreamBufferReceive xStreamBufferReceive + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferReceive( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer,
+                                    void *pvRxData,
+                                    size_t xBufferLengthBytes,
+                                    BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * An interrupt safe version of the API function that receives bytes from a + * stream buffer. + * + * Use xStreamBufferReceive() to read bytes from a stream buffer from a task. + * Use xStreamBufferReceiveFromISR() to read bytes from a stream buffer from an + * interrupt service routine (ISR). + * + * @param xStreamBuffer The handle of the stream buffer from which a stream + * is being received. + * + * @param pvRxData A pointer to the buffer into which the received bytes are + * copied. + * + * @param xBufferLengthBytes The length of the buffer pointed to by the + * pvRxData parameter. This sets the maximum number of bytes to receive in one + * call. xStreamBufferReceive will return as many bytes as possible up to a + * maximum set by xBufferLengthBytes. + * + * @param pxHigherPriorityTaskWoken It is possible that a stream buffer will + * have a task blocked on it waiting for space to become available. Calling + * xStreamBufferReceiveFromISR() can make space available, and so cause a task + * that is waiting for space to leave the Blocked state. If calling + * xStreamBufferReceiveFromISR() causes a task to leave the Blocked state, and + * the unblocked task has a priority higher than the currently executing task + * (the task that was interrupted), then, internally, + * xStreamBufferReceiveFromISR() will set *pxHigherPriorityTaskWoken to pdTRUE. + * If xStreamBufferReceiveFromISR() sets this value to pdTRUE, then normally a + * context switch should be performed before the interrupt is exited. That will + * ensure the interrupt returns directly to the highest priority Ready state + * task. *pxHigherPriorityTaskWoken should be set to pdFALSE before it is + * passed into the function. See the code example below for an example. + * + * @return The number of bytes read from the stream buffer, if any. + * + * Example use: +
+// A stream buffer that has already been created.
+StreamBuffer_t xStreamBuffer;
+
+void vAnInterruptServiceRoutine( void )
+{
+uint8_t ucRxData[ 20 ];
+size_t xReceivedBytes;
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;  // Initialised to pdFALSE.
+
+    // Receive the next stream from the stream buffer.
+    xReceivedBytes = xStreamBufferReceiveFromISR( xStreamBuffer,
+                                                  ( void * ) ucRxData,
+                                                  sizeof( ucRxData ),
+                                                  &xHigherPriorityTaskWoken );
+
+    if( xReceivedBytes > 0 )
+    {
+        // ucRxData contains xReceivedBytes read from the stream buffer.
+        // Process the stream here....
+    }
+
+    // If xHigherPriorityTaskWoken was set to pdTRUE inside
+    // xStreamBufferReceiveFromISR() then a task that has a priority above the
+    // priority of the currently executing task was unblocked and a context
+    // switch should be performed to ensure the ISR returns to the unblocked
+    // task.  In most FreeRTOS ports this is done by simply passing
+    // xHigherPriorityTaskWoken into taskYIELD_FROM_ISR(), which will test the
+    // variables value, and perform the context switch if necessary.  Check the
+    // documentation for the port in use for port specific instructions.
+    taskYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+}
+
+ * \defgroup xStreamBufferReceiveFromISR xStreamBufferReceiveFromISR + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferReceiveFromISR( StreamBufferHandle_t xStreamBuffer, + void *pvRxData, + size_t xBufferLengthBytes, + BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Deletes a stream buffer that was previously created using a call to + * xStreamBufferCreate() or xStreamBufferCreateStatic(). If the stream + * buffer was created using dynamic memory (that is, by xStreamBufferCreate()), + * then the allocated memory is freed. + * + * A stream buffer handle must not be used after the stream buffer has been + * deleted. + * + * @param xStreamBuffer The handle of the stream buffer to be deleted. + * + * \defgroup vStreamBufferDelete vStreamBufferDelete + * \ingroup StreamBufferManagement + */ +void vStreamBufferDelete( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see if it is full. A stream buffer is full if it + * does not have any free space, and therefore cannot accept any more data. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return If the stream buffer is full then pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferIsFull xStreamBufferIsFull + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferIsFull( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see if it is empty. A stream buffer is empty if + * it does not contain any data. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return If the stream buffer is empty then pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferIsEmpty xStreamBufferIsEmpty + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferIsEmpty( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Resets a stream buffer to its initial, empty, state. Any data that was in + * the stream buffer is discarded. A stream buffer can only be reset if there + * are no tasks blocked waiting to either send to or receive from the stream + * buffer. + * + * @param xStreamBuffer The handle of the stream buffer being reset. + * + * @return If the stream buffer is reset then pdPASS is returned. If there was + * a task blocked waiting to send to or read from the stream buffer then the + * stream buffer is not reset and pdFAIL is returned. + * + * \defgroup xStreamBufferReset xStreamBufferReset + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferReset( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see how much free space it contains, which is + * equal to the amount of data that can be sent to the stream buffer before it + * is full. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return The number of bytes that can be written to the stream buffer before + * the stream buffer would be full. + * + * \defgroup xStreamBufferSpacesAvailable xStreamBufferSpacesAvailable + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferSpacesAvailable( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer );
+
+ * + * Queries a stream buffer to see how much data it contains, which is equal to + * the number of bytes that can be read from the stream buffer before the stream + * buffer would be empty. + * + * @param xStreamBuffer The handle of the stream buffer being queried. + * + * @return The number of bytes that can be read from the stream buffer before + * the stream buffer would be empty. + * + * \defgroup xStreamBufferBytesAvailable xStreamBufferBytesAvailable + * \ingroup StreamBufferManagement + */ +size_t xStreamBufferBytesAvailable( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel );
+
+ * + * A stream buffer's trigger level is the number of bytes that must be in the + * stream buffer before a task that is blocked on the stream buffer to + * wait for data is moved out of the blocked state. For example, if a task is + * blocked on a read of an empty stream buffer that has a trigger level of 1 + * then the task will be unblocked when a single byte is written to the buffer + * or the task's block time expires. As another example, if a task is blocked + * on a read of an empty stream buffer that has a trigger level of 10 then the + * task will not be unblocked until the stream buffer contains at least 10 bytes + * or the task's block time expires. If a reading task's block time expires + * before the trigger level is reached then the task will still receive however + * many bytes are actually available. Setting a trigger level of 0 will result + * in a trigger level of 1 being used. It is not valid to specify a trigger + * level that is greater than the buffer size. + * + * A trigger level is set when the stream buffer is created, and can be modified + * using xStreamBufferSetTriggerLevel(). + * + * @param xStreamBuffer The handle of the stream buffer being updated. + * + * @param xTriggerLevel The new trigger level for the stream buffer. + * + * @return If xTriggerLevel was less than or equal to the stream buffer's length + * then the trigger level will be updated and pdTRUE is returned. Otherwise + * pdFALSE is returned. + * + * \defgroup xStreamBufferSetTriggerLevel xStreamBufferSetTriggerLevel + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferSetTriggerLevel( StreamBufferHandle_t xStreamBuffer, size_t xTriggerLevel ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbSEND_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is sent to a message buffer or stream buffer. If there was a task that + * was blocked on the message or stream buffer waiting for data to arrive then + * the sbSEND_COMPLETED() macro sends a notification to the task to remove it + * from the Blocked state. xStreamBufferSendCompletedFromISR() does the same + * thing. It is provided to enable application writers to implement their own + * version of sbSEND_COMPLETED(), and MUST NOT BE USED AT ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer to which data was + * written. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xStreamBufferSendCompletedFromISR(). If calling + * xStreamBufferSendCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xStreamBufferSendCompletedFromISR xStreamBufferSendCompletedFromISR + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferSendCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/** + * stream_buffer.h + * +
+BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken );
+
+ * + * For advanced users only. + * + * The sbRECEIVE_COMPLETED() macro is called from within the FreeRTOS APIs when + * data is read out of a message buffer or stream buffer. If there was a task + * that was blocked on the message or stream buffer waiting for data to arrive + * then the sbRECEIVE_COMPLETED() macro sends a notification to the task to + * remove it from the Blocked state. xStreamBufferReceiveCompletedFromISR() + * does the same thing. It is provided to enable application writers to + * implement their own version of sbRECEIVE_COMPLETED(), and MUST NOT BE USED AT + * ANY OTHER TIME. + * + * See the example implemented in FreeRTOS/Demo/Minimal/MessageBufferAMP.c for + * additional information. + * + * @param xStreamBuffer The handle of the stream buffer from which data was + * read. + * + * @param pxHigherPriorityTaskWoken *pxHigherPriorityTaskWoken should be + * initialised to pdFALSE before it is passed into + * xStreamBufferReceiveCompletedFromISR(). If calling + * xStreamBufferReceiveCompletedFromISR() removes a task from the Blocked state, + * and the task has a priority above the priority of the currently running task, + * then *pxHigherPriorityTaskWoken will get set to pdTRUE indicating that a + * context switch should be performed before exiting the ISR. + * + * @return If a task was removed from the Blocked state then pdTRUE is returned. + * Otherwise pdFALSE is returned. + * + * \defgroup xStreamBufferReceiveCompletedFromISR xStreamBufferReceiveCompletedFromISR + * \ingroup StreamBufferManagement + */ +BaseType_t xStreamBufferReceiveCompletedFromISR( StreamBufferHandle_t xStreamBuffer, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + +/* Functions below here are not part of the public API. */ +StreamBufferHandle_t xStreamBufferGenericCreate( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer ) PRIVILEGED_FUNCTION; + +StreamBufferHandle_t xStreamBufferGenericCreateStatic( size_t xBufferSizeBytes, + size_t xTriggerLevelBytes, + BaseType_t xIsMessageBuffer, + uint8_t * const pucStreamBufferStorageArea, + StaticStreamBuffer_t * const pxStaticStreamBuffer ) PRIVILEGED_FUNCTION; + +size_t xStreamBufferNextMessageLengthBytes( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + +#if( configUSE_TRACE_FACILITY == 1 ) + void vStreamBufferSetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer, UBaseType_t uxStreamBufferNumber ) PRIVILEGED_FUNCTION; + UBaseType_t uxStreamBufferGetStreamBufferNumber( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; + uint8_t ucStreamBufferGetStreamBufferType( StreamBufferHandle_t xStreamBuffer ) PRIVILEGED_FUNCTION; +#endif + +#if defined( __cplusplus ) +} +#endif + +#endif /* !defined( STREAM_BUFFER_H ) */ diff --git a/lib/FreeRTOS-SAMD51/src/task.h b/lib/FreeRTOS-SAMD51/src/task.h new file mode 100644 index 0000000..2e1253e --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/task.h @@ -0,0 +1,2431 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef INC_TASK_H +#define INC_TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V10.2.0" +#define tskKERNEL_VERSION_MAJOR 10 +#define tskKERNEL_VERSION_MINOR 2 +#define tskKERNEL_VERSION_BUILD 0 + +/* MPU region parameters passed in ulParameters + * of MemoryRegion_t struct. */ +#define tskMPU_REGION_READ_ONLY ( 1UL << 0UL ) +#define tskMPU_REGION_READ_WRITE ( 1UL << 1UL ) +#define tskMPU_REGION_EXECUTE_NEVER ( 1UL << 2UL ) +#define tskMPU_REGION_NORMAL_MEMORY ( 1UL << 3UL ) +#define tskMPU_REGION_DEVICE_MEMORY ( 1UL << 4UL ) + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an TaskHandle_t variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \defgroup TaskHandle_t TaskHandle_t + * \ingroup Tasks + */ +struct tskTaskControlBlock; /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +typedef struct tskTaskControlBlock* TaskHandle_t; + +/* + * Defines the prototype to which the application task hook function must + * conform. + */ +typedef BaseType_t (*TaskHookFunction_t)( void * ); + +/* Task states returned by eTaskGetState. */ +typedef enum +{ + eRunning = 0, /* A task is querying the state of itself, so must be running. */ + eReady, /* The task being queried is in a read or pending ready list. */ + eBlocked, /* The task being queried is in the Blocked state. */ + eSuspended, /* The task being queried is in the Suspended state, or is in the Blocked state with an infinite time out. */ + eDeleted, /* The task being queried has been deleted, but its TCB has not yet been freed. */ + eInvalid /* Used as an 'invalid state' value. */ +} eTaskState; + +/* Actions that can be performed when vTaskNotify() is called. */ +typedef enum +{ + eNoAction = 0, /* Notify the task without updating its notify value. */ + eSetBits, /* Set bits in the task's notification value. */ + eIncrement, /* Increment the task's notification value. */ + eSetValueWithOverwrite, /* Set the task's notification value to a specific value even if the previous value has not yet been read by the task. */ + eSetValueWithoutOverwrite /* Set the task's notification value if the previous value has been read by the task. */ +} eNotifyAction; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + BaseType_t xOverflowCount; + TickType_t xTimeOnEntering; +} TimeOut_t; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + uint32_t ulLengthInBytes; + uint32_t ulParameters; +} MemoryRegion_t; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMETERS +{ + TaskFunction_t pvTaskCode; + const char * const pcName; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + configSTACK_DEPTH_TYPE usStackDepth; + void *pvParameters; + UBaseType_t uxPriority; + StackType_t *puxStackBuffer; + MemoryRegion_t xRegions[ portNUM_CONFIGURABLE_REGIONS ]; + #if ( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + StaticTask_t * const pxTaskBuffer; + #endif +} TaskParameters_t; + +/* Used with the uxTaskGetSystemState() function to return the state of each task +in the system. */ +typedef struct xTASK_STATUS +{ + TaskHandle_t xHandle; /* The handle of the task to which the rest of the information in the structure relates. */ + const char *pcTaskName; /* A pointer to the task's name. This value will be invalid if the task was deleted since the structure was populated! */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + UBaseType_t xTaskNumber; /* A number unique to the task. */ + eTaskState eCurrentState; /* The state in which the task existed when the structure was populated. */ + UBaseType_t uxCurrentPriority; /* The priority at which the task was running (may be inherited) when the structure was populated. */ + UBaseType_t uxBasePriority; /* The priority to which the task will return if the task's current priority has been inherited to avoid unbounded priority inversion when obtaining a mutex. Only valid if configUSE_MUTEXES is defined as 1 in FreeRTOSConfig.h. */ + uint32_t ulRunTimeCounter; /* The total run time allocated to the task so far, as defined by the run time stats clock. See http://www.freertos.org/rtos-run-time-stats.html. Only valid when configGENERATE_RUN_TIME_STATS is defined as 1 in FreeRTOSConfig.h. */ + StackType_t *pxStackBase; /* Points to the lowest address of the task's stack area. */ + configSTACK_DEPTH_TYPE usStackHighWaterMark; /* The minimum amount of stack space that has remained for the task since the task was created. The closer this value is to zero the closer the task has come to overflowing its stack. */ +} TaskStatus_t; + +/* Possible return values for eTaskConfirmSleepModeStatus(). */ +typedef enum +{ + eAbortSleep = 0, /* A task has been made ready or a context switch pended since portSUPPORESS_TICKS_AND_SLEEP() was called - abort entering a sleep mode. */ + eStandardSleep, /* Enter a sleep mode that will not last any longer than the expected idle time. */ + eNoTasksWaitingTimeout /* No tasks are waiting for a timeout so it is safe to enter a sleep mode that can only be exited by an external interrupt. */ +} eSleepModeStatus; + +/** + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( UBaseType_t ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \defgroup taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \defgroup taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() +#define taskENTER_CRITICAL_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \defgroup taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() +#define taskEXIT_CRITICAL_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( x ) +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \defgroup taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \defgroup taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). taskSCHEDULER_SUSPENDED is +0 to generate more optimal code when configASSERT() is defined as the constant +is used in assert() statements. */ +#define taskSCHEDULER_SUSPENDED ( ( BaseType_t ) 0 ) +#define taskSCHEDULER_NOT_STARTED ( ( BaseType_t ) 1 ) +#define taskSCHEDULER_RUNNING ( ( BaseType_t ) 2 ) + + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ BaseType_t xTaskCreate(
+							  TaskFunction_t pvTaskCode,
+							  const char * const pcName,
+							  configSTACK_DEPTH_TYPE usStackDepth,
+							  void *pvParameters,
+							  UBaseType_t uxPriority,
+							  TaskHandle_t *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreate() then both blocks of memory are automatically dynamically + * allocated inside the xTaskCreate() function. (see + * http://www.freertos.org/a00111.html). If a task is created using + * xTaskCreateStatic() then the application writer must provide the required + * memory. xTaskCreateStatic() therefore allows a task to be created without + * using any dynamic memory allocation. + * + * See xTaskCreateStatic() for a version that does not use any dynamic memory + * allocation. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by configMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static uint8_t ucParameterToPass;
+ TaskHandle_t xHandle = NULL;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+     configASSERT( xHandle );
+
+	 // Use the handle to delete the task.
+     if( xHandle != NULL )
+     {
+	     vTaskDelete( xHandle );
+     }
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + BaseType_t xTaskCreate( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const configSTACK_DEPTH_TYPE usStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ TaskHandle_t xTaskCreateStatic( TaskFunction_t pvTaskCode,
+								 const char * const pcName,
+								 uint32_t ulStackDepth,
+								 void *pvParameters,
+								 UBaseType_t uxPriority,
+								 StackType_t *pxStackBuffer,
+								 StaticTask_t *pxTaskBuffer );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreate() then both blocks of memory are automatically dynamically + * allocated inside the xTaskCreate() function. (see + * http://www.freertos.org/a00111.html). If a task is created using + * xTaskCreateStatic() then the application writer must provide the required + * memory. xTaskCreateStatic() therefore allows a task to be created without + * using any dynamic memory allocation. + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. The maximum length of the string is defined by + * configMAX_TASK_NAME_LEN in FreeRTOSConfig.h. + * + * @param ulStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 32-bits wide and ulStackDepth is defined as 100 then 400 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task will run. + * + * @param pxStackBuffer Must point to a StackType_t array that has at least + * ulStackDepth indexes - the array will then be used as the task's stack, + * removing the need for the stack to be allocated dynamically. + * + * @param pxTaskBuffer Must point to a variable of type StaticTask_t, which will + * then be used to hold the task's data structures, removing the need for the + * memory to be allocated dynamically. + * + * @return If neither pxStackBuffer or pxTaskBuffer are NULL, then the task will + * be created and a handle to the created task is returned. If either + * pxStackBuffer or pxTaskBuffer are NULL then the task will not be created and + * NULL is returned. + * + * Example usage: +
+
+    // Dimensions the buffer that the task being created will use as its stack.
+    // NOTE:  This is the number of words the stack will hold, not the number of
+    // bytes.  For example, if each stack item is 32-bits, and this is set to 100,
+    // then 400 bytes (100 * 32-bits) will be allocated.
+    #define STACK_SIZE 200
+
+    // Structure that will hold the TCB of the task being created.
+    StaticTask_t xTaskBuffer;
+
+    // Buffer that the task being created will use as its stack.  Note this is
+    // an array of StackType_t variables.  The size of StackType_t is dependent on
+    // the RTOS port.
+    StackType_t xStack[ STACK_SIZE ];
+
+    // Function that implements the task being created.
+    void vTaskCode( void * pvParameters )
+    {
+        // The parameter value is expected to be 1 as 1 is passed in the
+        // pvParameters value in the call to xTaskCreateStatic().
+        configASSERT( ( uint32_t ) pvParameters == 1UL );
+
+        for( ;; )
+        {
+            // Task code goes here.
+        }
+    }
+
+    // Function that creates a task.
+    void vOtherFunction( void )
+    {
+        TaskHandle_t xHandle = NULL;
+
+        // Create the task without using any dynamic memory allocation.
+        xHandle = xTaskCreateStatic(
+                      vTaskCode,       // Function that implements the task.
+                      "NAME",          // Text name for the task.
+                      STACK_SIZE,      // Stack size in words, not bytes.
+                      ( void * ) 1,    // Parameter passed into the task.
+                      tskIDLE_PRIORITY,// Priority at which the task is created.
+                      xStack,          // Array to use as the task's stack.
+                      &xTaskBuffer );  // Variable to hold the task's data structure.
+
+        // puxStackBuffer and pxTaskBuffer were not NULL, so the task will have
+        // been created, and xHandle will be the task's handle.  Use the handle
+        // to suspend the task.
+        vTaskSuspend( xHandle );
+    }
+   
+ * \defgroup xTaskCreateStatic xTaskCreateStatic + * \ingroup Tasks + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + TaskHandle_t xTaskCreateStatic( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + StackType_t * const puxStackBuffer, + StaticTask_t * const pxTaskBuffer ) PRIVILEGED_FUNCTION; +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * task. h + *
+ BaseType_t xTaskCreateRestricted( TaskParameters_t *pxTaskDefinition, TaskHandle_t *pxCreatedTask );
+ * + * Only available when configSUPPORT_DYNAMIC_ALLOCATION is set to 1. + * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * See xTaskCreateRestrictedStatic() for a version that does not use any + * dynamic memory allocation. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+// Create an TaskParameters_t structure that defines the task to be created.
+static const TaskParameters_t xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+TaskHandle_t xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// and/or timer task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + BaseType_t xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ BaseType_t xTaskCreateRestrictedStatic( TaskParameters_t *pxTaskDefinition, TaskHandle_t *pxCreatedTask );
+ * + * Only available when configSUPPORT_STATIC_ALLOCATION is set to 1. + * + * xTaskCreateRestrictedStatic() should only be used in systems that include an + * MPU implementation. + * + * Internally, within the FreeRTOS implementation, tasks use two blocks of + * memory. The first block is used to hold the task's data structures. The + * second block is used by the task as its stack. If a task is created using + * xTaskCreateRestricted() then the stack is provided by the application writer, + * and the memory used to hold the task's data structure is automatically + * dynamically allocated inside the xTaskCreateRestricted() function. If a task + * is created using xTaskCreateRestrictedStatic() then the application writer + * must provide the memory used to hold the task's data structures too. + * xTaskCreateRestrictedStatic() therefore allows a memory protected task to be + * created without using any dynamic memory allocation. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. If configSUPPORT_STATIC_ALLOCATION is set to 1 the structure + * contains an additional member, which is used to point to a variable of type + * StaticTask_t - which is then used to hold the task's data structure. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file projdefs.h + * + * Example usage: +
+// Create an TaskParameters_t structure that defines the task to be created.
+// The StaticTask_t variable is only included in the structure when
+// configSUPPORT_STATIC_ALLOCATION is set to 1.  The PRIVILEGED_DATA macro can
+// be used to force the variable into the RTOS kernel's privileged data area.
+static PRIVILEGED_DATA StaticTask_t xTaskBuffer;
+static const TaskParameters_t xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+
+	&xTaskBuffer; // Holds the task's data structure.
+};
+
+int main( void )
+{
+TaskHandle_t xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// and/or timer task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestrictedStatic xTaskCreateRestrictedStatic + * \ingroup Tasks + */ +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + BaseType_t xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) PRIVILEGED_FUNCTION; +#endif + +/** + * task. h + *
+ void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an MemoryRegion_t structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of MemoryRegion_t structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const MemoryRegion_t xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( TaskHandle_t xTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernel's management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param xTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( TaskHandle_t xTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( const TickType_t xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_PERIOD_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a periodic task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const TickType_t xDelay = 500 / portTICK_PERIOD_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( const TickType_t xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( TickType_t *pxPreviousWakeTime, const TickType_t xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by periodic + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_PERIOD_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskAbortDelay( TaskHandle_t xTask );
+ * + * INCLUDE_xTaskAbortDelay must be defined as 1 in FreeRTOSConfig.h for this + * function to be available. + * + * A task will enter the Blocked state when it is waiting for an event. The + * event it is waiting for can be a temporal event (waiting for a time), such + * as when vTaskDelay() is called, or an event on an object, such as when + * xQueueReceive() or ulTaskNotifyTake() is called. If the handle of a task + * that is in the Blocked state is used in a call to xTaskAbortDelay() then the + * task will leave the Blocked state, and return from whichever function call + * placed the task into the Blocked state. + * + * @param xTask The handle of the task to remove from the Blocked state. + * + * @return If the task referenced by xTask was not in the Blocked state then + * pdFAIL is returned. Otherwise pdPASS is returned. + * + * \defgroup xTaskAbortDelay xTaskAbortDelay + * \ingroup TaskCtrl + */ +BaseType_t xTaskAbortDelay( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param xTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of xTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask );
+ * + * A version of uxTaskPriorityGet() that can be used from an ISR. + */ +UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
eTaskState eTaskGetState( TaskHandle_t xTask );
+ * + * INCLUDE_eTaskGetState must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the state of any task. States are encoded by the eTaskState + * enumerated type. + * + * @param xTask Handle of the task to be queried. + * + * @return The state of xTask at the time the function was called. Note the + * state of the task might change between the function being called, and the + * functions return value being tested by the calling task. + */ +eTaskState eTaskGetState( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * Populates a TaskStatus_t structure with information about a task. + * + * @param xTask Handle of the task being queried. If xTask is NULL then + * information will be returned about the calling task. + * + * @param pxTaskStatus A pointer to the TaskStatus_t structure that will be + * filled with information about the task referenced by the handle passed using + * the xTask parameter. + * + * @xGetFreeStackSpace The TaskStatus_t structure contains a member to report + * the stack high water mark of the task being queried. Calculating the stack + * high water mark takes a relatively long time, and can make the system + * temporarily unresponsive - so the xGetFreeStackSpace parameter is provided to + * allow the high water mark checking to be skipped. The high watermark value + * will only be written to the TaskStatus_t structure if xGetFreeStackSpace is + * not set to pdFALSE; + * + * @param eState The TaskStatus_t structure contains a member to report the + * state of the task being queried. Obtaining the task state is not as fast as + * a simple assignment - so the eState parameter is provided to allow the state + * information to be omitted from the TaskStatus_t structure. To obtain state + * information then set eState to eInvalid - otherwise the value passed in + * eState will be reported as the task state in the TaskStatus_t structure. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+ TaskStatus_t xTaskDetails;
+
+    // Obtain the handle of a task from its name.
+    xHandle = xTaskGetHandle( "Task_Name" );
+
+    // Check the handle is not NULL.
+    configASSERT( xHandle );
+
+    // Use the handle to obtain further information about the task.
+    vTaskGetInfo( xHandle,
+                  &xTaskDetails,
+                  pdTRUE, // Include the high water mark in xTaskDetails.
+                  eInvalid ); // Include the task state in xTaskDetails.
+ }
+   
+ * \defgroup vTaskGetInfo vTaskGetInfo + * \ingroup TaskCtrl + */ +void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param xTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( TaskHandle_t xTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param xTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( TaskHandle_t xTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( TaskHandle_t xTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one or more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param xTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with its priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( TaskHandle_t xTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one or more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * xTaskResumeFromISR() should not be used to synchronise a task with an + * interrupt if there is a chance that the interrupt could arrive prior to the + * task being suspended - as this can lead to interrupts being missed. Use of a + * semaphore as a synchronisation mechanism would avoid this eventuality. + * + * @param xTaskToResume Handle to the task being readied. + * + * @return pdTRUE if resuming the task should result in a context switch, + * otherwise pdFALSE. This is used by the ISR to determine if a context switch + * may be required following the ISR. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * NOTE: At the time of writing only the x86 real mode port, which runs on a PC + * in place of DOS, implements this function. + * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends the scheduler without disabling interrupts. Context switches will + * not occur while the scheduler is suspended. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskResumeAll( void );
+ * + * Resumes scheduler activity after it was suspended by a call to + * vTaskSuspendAll(). + * + * xTaskResumeAll() only resumes the scheduler. It does not unsuspend tasks + * that were previously suspended by a call to vTaskSuspend(). + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +BaseType_t xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
TickType_t xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \defgroup xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +TickType_t xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
TickType_t xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that TickType_t is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \defgroup xTaskGetTickCountFromISR xTaskGetTickCountFromISR + * \ingroup TaskUtils + */ +TickType_t xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
uint16_t uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \defgroup uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +UBaseType_t uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char *pcTaskGetName( TaskHandle_t xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQuery. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. + * + * \defgroup pcTaskGetName pcTaskGetName + * \ingroup TaskUtils + */ +char *pcTaskGetName( TaskHandle_t xTaskToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task. h + *
TaskHandle_t xTaskGetHandle( const char *pcNameToQuery );
+ * + * NOTE: This function takes a relatively long time to complete and should be + * used sparingly. + * + * @return The handle of the task that has the human readable name pcNameToQuery. + * NULL is returned if no matching name is found. INCLUDE_xTaskGetHandle + * must be set to 1 in FreeRTOSConfig.h for pcTaskGetHandle() to be available. + * + * \defgroup pcTaskGetHandle pcTaskGetHandle + * \ingroup TaskUtils + */ +TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task.h + *
UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + * same except for their return type. Using configSTACK_DEPTH_TYPE allows the + * user to determine the return type. It gets around the problem of the value + * overflowing on 8-bit types without breaking backward compatibility for + * applications that expect an 8-bit return type. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in words, so + * actual spaces on the stack rather than bytes) since the task referenced by + * xTask was created. + */ +UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark2 must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + * same except for their return type. Using configSTACK_DEPTH_TYPE allows the + * user to determine the return type. It gets around the problem of the value + * overflowing on 8-bit types without breaking backward compatibility for + * applications that expect an 8-bit return type. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in words, so + * actual spaces on the stack rather than bytes) since the task referenced by + * xTask was created. + */ +configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/* When using trace macros it is sometimes necessary to include task.h before +FreeRTOS.h. When this is done TaskHookFunction_t will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( TaskHandle_t xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. Do not + * call from an interrupt service routine - call + * xTaskGetApplicationTaskTagFromISR() instead. + */ + TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. Can + * be called from an interrupt service routine. + */ + TaskHookFunction_t xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +#if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + + /* Each task contains an array of pointers that is dimensioned by the + configNUM_THREAD_LOCAL_STORAGE_POINTERS setting in FreeRTOSConfig.h. The + kernel does not use the pointers itself, so the application writer can use + the pointers for any purpose they wish. The following two functions are + used to set and query a pointer respectively. */ + void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) PRIVILEGED_FUNCTION; + void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) PRIVILEGED_FUNCTION; + +#endif + +/** + * task.h + *
BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. The return value is the value returned by the task hook function + * registered by the user. + */ +BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +TaskHandle_t xTaskGetIdleTaskHandle( void ) PRIVILEGED_FUNCTION; + +/** + * configUSE_TRACE_FACILITY must be defined as 1 in FreeRTOSConfig.h for + * uxTaskGetSystemState() to be available. + * + * uxTaskGetSystemState() populates an TaskStatus_t structure for each task in + * the system. TaskStatus_t structures contain, among other things, members + * for the task handle, task name, task priority, task state, and total amount + * of run time consumed by the task. See the TaskStatus_t structure + * definition in this file for the full member list. + * + * NOTE: This function is intended for debugging use only as its use results in + * the scheduler remaining suspended for an extended period. + * + * @param pxTaskStatusArray A pointer to an array of TaskStatus_t structures. + * The array must contain at least one TaskStatus_t structure for each task + * that is under the control of the RTOS. The number of tasks under the control + * of the RTOS can be determined using the uxTaskGetNumberOfTasks() API function. + * + * @param uxArraySize The size of the array pointed to by the pxTaskStatusArray + * parameter. The size is specified as the number of indexes in the array, or + * the number of TaskStatus_t structures contained in the array, not by the + * number of bytes in the array. + * + * @param pulTotalRunTime If configGENERATE_RUN_TIME_STATS is set to 1 in + * FreeRTOSConfig.h then *pulTotalRunTime is set by uxTaskGetSystemState() to the + * total run time (as defined by the run time stats clock, see + * http://www.freertos.org/rtos-run-time-stats.html) since the target booted. + * pulTotalRunTime can be set to NULL to omit the total run time information. + * + * @return The number of TaskStatus_t structures that were populated by + * uxTaskGetSystemState(). This should equal the number returned by the + * uxTaskGetNumberOfTasks() API function, but will be zero if the value passed + * in the uxArraySize parameter was too small. + * + * Example usage: +
+    // This example demonstrates how a human readable table of run time stats
+	// information is generated from raw data provided by uxTaskGetSystemState().
+	// The human readable table is written to pcWriteBuffer
+	void vTaskGetRunTimeStats( char *pcWriteBuffer )
+	{
+	TaskStatus_t *pxTaskStatusArray;
+	volatile UBaseType_t uxArraySize, x;
+	uint32_t ulTotalRunTime, ulStatsAsPercentage;
+
+		// Make sure the write buffer does not contain a string.
+		*pcWriteBuffer = 0x00;
+
+		// Take a snapshot of the number of tasks in case it changes while this
+		// function is executing.
+		uxArraySize = uxTaskGetNumberOfTasks();
+
+		// Allocate a TaskStatus_t structure for each task.  An array could be
+		// allocated statically at compile time.
+		pxTaskStatusArray = pvPortMalloc( uxArraySize * sizeof( TaskStatus_t ) );
+
+		if( pxTaskStatusArray != NULL )
+		{
+			// Generate raw status information about each task.
+			uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalRunTime );
+
+			// For percentage calculations.
+			ulTotalRunTime /= 100UL;
+
+			// Avoid divide by zero errors.
+			if( ulTotalRunTime > 0 )
+			{
+				// For each populated position in the pxTaskStatusArray array,
+				// format the raw data as human readable ASCII data
+				for( x = 0; x < uxArraySize; x++ )
+				{
+					// What percentage of the total run time has the task used?
+					// This will always be rounded down to the nearest integer.
+					// ulTotalRunTimeDiv100 has already been divided by 100.
+					ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalRunTime;
+
+					if( ulStatsAsPercentage > 0UL )
+					{
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage );
+					}
+					else
+					{
+						// If the percentage is zero here then the task has
+						// consumed less than 1% of the total run time.
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter );
+					}
+
+					pcWriteBuffer += strlen( ( char * ) pcWriteBuffer );
+				}
+			}
+
+			// The array is no longer needed, free the memory it consumes.
+			vPortFree( pxTaskStatusArray );
+		}
+	}
+	
+ */ +UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY and configUSE_STATS_FORMATTING_FUNCTIONS must + * both be defined as 1 for this function to be available. See the + * configuration section of the FreeRTOS.org website for more information. + * + * NOTE 1: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many of the + * demo applications. Do not consider it to be part of the scheduler. + * + * vTaskList() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that displays task + * names, states and stack usage. + * + * vTaskList() has a dependency on the sprintf() C library function that might + * bloat the code size, use a lot of stack, and provide different results on + * different platforms. An alternative, tiny, third party, and limited + * functionality implementation of sprintf() is provided in many of the + * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note + * printf-stdarg.c does not provide a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly through a + * call to vTaskList(). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ASCII form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \defgroup vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( char * pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS and configUSE_STATS_FORMATTING_FUNCTIONS + * must both be defined as 1 for this function to be available. The application + * must also then provide definitions for + * portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and portGET_RUN_TIME_COUNTER_VALUE() + * to configure a peripheral timer/counter and return the timers current count + * value respectively. The counter should be at least 10 times the frequency of + * the tick count. + * + * NOTE 1: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * NOTE 2: + * + * This function is provided for convenience only, and is used by many of the + * demo applications. Do not consider it to be part of the scheduler. + * + * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that displays the + * amount of time each task has spent in the Running state in both absolute and + * percentage terms. + * + * vTaskGetRunTimeStats() has a dependency on the sprintf() C library function + * that might bloat the code size, use a lot of stack, and provide different + * results on different platforms. An alternative, tiny, third party, and + * limited functionality implementation of sprintf() is provided in many of the + * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note + * printf-stdarg.c does not provide a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() directly + * to get access to raw stats data, rather than indirectly through a call to + * vTaskGetRunTimeStats(). + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ASCII form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \defgroup vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( char *pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** +* task. h +*
TickType_t xTaskGetIdleRunTimeCounter( void );
+* +* configGENERATE_RUN_TIME_STATS and configUSE_STATS_FORMATTING_FUNCTIONS +* must both be defined as 1 for this function to be available. The application +* must also then provide definitions for +* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and portGET_RUN_TIME_COUNTER_VALUE() +* to configure a peripheral timer/counter and return the timers current count +* value respectively. The counter should be at least 10 times the frequency of +* the tick count. +* +* Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total +* accumulated execution time being stored for each task. The resolution +* of the accumulated time value depends on the frequency of the timer +* configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. +* While uxTaskGetSystemState() and vTaskGetRunTimeStats() writes the total +* execution time of each task into a buffer, xTaskGetIdleRunTimeCounter() +* returns the total execution time of just the idle task. +* +* @return The total run time of the idle task. This is the amount of time the +* idle task has actually been executing. The unit of time is dependent on the +* frequency configured using the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and +* portGET_RUN_TIME_COUNTER_VALUE() macros. +* +* \defgroup xTaskGetIdleRunTimeCounter xTaskGetIdleRunTimeCounter +* \ingroup TaskUtils +*/ +TickType_t xTaskGetIdleRunTimeCounter( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @param ulValue Data that can be sent with the notification. How the data is + * used depends on the value of the eAction parameter. + * + * @param eAction Specifies how the notification updates the task's notification + * value, if at all. Valid values for eAction are as follows: + * + * eSetBits - + * The task's notification value is bitwise ORed with ulValue. xTaskNofify() + * always returns pdPASS in this case. + * + * eIncrement - + * The task's notification value is incremented. ulValue is not used and + * xTaskNotify() always returns pdPASS in this case. + * + * eSetValueWithOverwrite - + * The task's notification value is set to the value of ulValue, even if the + * task being notified had not yet processed the previous notification (the + * task already had a notification pending). xTaskNotify() always returns + * pdPASS in this case. + * + * eSetValueWithoutOverwrite - + * If the task being notified did not already have a notification pending then + * the task's notification value is set to ulValue and xTaskNotify() will + * return pdPASS. If the task being notified already had a notification + * pending then no action is performed and pdFAIL is returned. + * + * eNoAction - + * The task receives a notification without its notification value being + * updated. ulValue is not used and xTaskNotify() always returns pdPASS in + * this case. + * + * pulPreviousNotificationValue - + * Can be used to pass out the subject task's notification value before any + * bits are modified by the notify function. + * + * @return Dependent on the value of eAction. See the description of the + * eAction parameter. + * + * \defgroup xTaskNotify xTaskNotify + * \ingroup TaskNotifications + */ +BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) PRIVILEGED_FUNCTION; +#define xTaskNotify( xTaskToNotify, ulValue, eAction ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL ) +#define xTaskNotifyAndQuery( xTaskToNotify, ulValue, eAction, pulPreviousNotifyValue ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotifyValue ) ) + +/** + * task. h + *
BaseType_t xTaskNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, BaseType_t *pxHigherPriorityTaskWoken );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * A version of xTaskNotify() that can be used from an interrupt service routine + * (ISR). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @param ulValue Data that can be sent with the notification. How the data is + * used depends on the value of the eAction parameter. + * + * @param eAction Specifies how the notification updates the task's notification + * value, if at all. Valid values for eAction are as follows: + * + * eSetBits - + * The task's notification value is bitwise ORed with ulValue. xTaskNofify() + * always returns pdPASS in this case. + * + * eIncrement - + * The task's notification value is incremented. ulValue is not used and + * xTaskNotify() always returns pdPASS in this case. + * + * eSetValueWithOverwrite - + * The task's notification value is set to the value of ulValue, even if the + * task being notified had not yet processed the previous notification (the + * task already had a notification pending). xTaskNotify() always returns + * pdPASS in this case. + * + * eSetValueWithoutOverwrite - + * If the task being notified did not already have a notification pending then + * the task's notification value is set to ulValue and xTaskNotify() will + * return pdPASS. If the task being notified already had a notification + * pending then no action is performed and pdFAIL is returned. + * + * eNoAction - + * The task receives a notification without its notification value being + * updated. ulValue is not used and xTaskNotify() always returns pdPASS in + * this case. + * + * @param pxHigherPriorityTaskWoken xTaskNotifyFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the + * task to which the notification was sent to leave the Blocked state, and the + * unblocked task has a priority higher than the currently running task. If + * xTaskNotifyFromISR() sets this value to pdTRUE then a context switch should + * be requested before the interrupt is exited. How a context switch is + * requested from an ISR is dependent on the port - see the documentation page + * for the port in use. + * + * @return Dependent on the value of eAction. See the description of the + * eAction parameter. + * + * \defgroup xTaskNotify xTaskNotify + * \ingroup TaskNotifications + */ +BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +#define xTaskNotifyFromISR( xTaskToNotify, ulValue, eAction, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL, ( pxHigherPriorityTaskWoken ) ) +#define xTaskNotifyAndQueryFromISR( xTaskToNotify, ulValue, eAction, pulPreviousNotificationValue, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotificationValue ), ( pxHigherPriorityTaskWoken ) ) + +/** + * task. h + *
BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * A notification sent to a task will remain pending until it is cleared by the + * task calling xTaskNotifyWait() or ulTaskNotifyTake(). If the task was + * already in the Blocked state to wait for a notification when the notification + * arrives then the task will automatically be removed from the Blocked state + * (unblocked) and the notification cleared. + * + * A task can use xTaskNotifyWait() to [optionally] block to wait for a + * notification to be pending, or ulTaskNotifyTake() to [optionally] block + * to wait for its notification value to have a non-zero value. The task does + * not consume any CPU time while it is in the Blocked state. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param ulBitsToClearOnEntry Bits that are set in ulBitsToClearOnEntry value + * will be cleared in the calling task's notification value before the task + * checks to see if any notifications are pending, and optionally blocks if no + * notifications are pending. Setting ulBitsToClearOnEntry to ULONG_MAX (if + * limits.h is included) or 0xffffffffUL (if limits.h is not included) will have + * the effect of resetting the task's notification value to 0. Setting + * ulBitsToClearOnEntry to 0 will leave the task's notification value unchanged. + * + * @param ulBitsToClearOnExit If a notification is pending or received before + * the calling task exits the xTaskNotifyWait() function then the task's + * notification value (see the xTaskNotify() API function) is passed out using + * the pulNotificationValue parameter. Then any bits that are set in + * ulBitsToClearOnExit will be cleared in the task's notification value (note + * *pulNotificationValue is set before any bits are cleared). Setting + * ulBitsToClearOnExit to ULONG_MAX (if limits.h is included) or 0xffffffffUL + * (if limits.h is not included) will have the effect of resetting the task's + * notification value to 0 before the function exits. Setting + * ulBitsToClearOnExit to 0 will leave the task's notification value unchanged + * when the function exits (in which case the value passed out in + * pulNotificationValue will match the task's notification value). + * + * @param pulNotificationValue Used to pass the task's notification value out + * of the function. Note the value passed out will not be effected by the + * clearing of any bits caused by ulBitsToClearOnExit being non-zero. + * + * @param xTicksToWait The maximum amount of time that the task should wait in + * the Blocked state for a notification to be received, should a notification + * not already be pending when xTaskNotifyWait() was called. The task + * will not consume any processing time while it is in the Blocked state. This + * is specified in kernel ticks, the macro pdMS_TO_TICSK( value_in_ms ) can be + * used to convert a time specified in milliseconds to a time specified in + * ticks. + * + * @return If a notification was received (including notifications that were + * already pending when xTaskNotifyWait was called) then pdPASS is + * returned. Otherwise pdFAIL is returned. + * + * \defgroup xTaskNotifyWait xTaskNotifyWait + * \ingroup TaskNotifications + */ +BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotifyGive( TaskHandle_t xTaskToNotify );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro + * to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * xTaskNotifyGive() is a helper macro intended for use when task notifications + * are used as light weight and faster binary or counting semaphore equivalents. + * Actual FreeRTOS semaphores are given using the xSemaphoreGive() API function, + * the equivalent action that instead uses a task notification is + * xTaskNotifyGive(). + * + * When task notifications are being used as a binary or counting semaphore + * equivalent then the task being notified should wait for the notification + * using the ulTaskNotificationTake() API function rather than the + * xTaskNotifyWait() API function. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details. + * + * @param xTaskToNotify The handle of the task being notified. The handle to a + * task can be returned from the xTaskCreate() API function used to create the + * task, and the handle of the currently running task can be obtained by calling + * xTaskGetCurrentTaskHandle(). + * + * @return xTaskNotifyGive() is a macro that calls xTaskNotify() with the + * eAction parameter set to eIncrement - so pdPASS is always returned. + * + * \defgroup xTaskNotifyGive xTaskNotifyGive + * \ingroup TaskNotifications + */ +#define xTaskNotifyGive( xTaskToNotify ) xTaskGenericNotify( ( xTaskToNotify ), ( 0 ), eIncrement, NULL ) + +/** + * task. h + *
void vTaskNotifyGiveFromISR( TaskHandle_t xTaskHandle, BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro
+ * to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * A version of xTaskNotifyGive() that can be called from an interrupt service
+ * routine (ISR).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * vTaskNotifyGiveFromISR() is intended for use when task notifications are
+ * used as light weight and faster binary or counting semaphore equivalents.
+ * Actual FreeRTOS semaphores are given from an ISR using the
+ * xSemaphoreGiveFromISR() API function, the equivalent action that instead uses
+ * a task notification is vTaskNotifyGiveFromISR().
+ *
+ * When task notifications are being used as a binary or counting semaphore
+ * equivalent then the task being notified should wait for the notification
+ * using the ulTaskNotificationTake() API function rather than the
+ * xTaskNotifyWait() API function.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @param pxHigherPriorityTaskWoken  vTaskNotifyGiveFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the
+ * task to which the notification was sent to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently running task.  If
+ * vTaskNotifyGiveFromISR() sets this value to pdTRUE then a context switch
+ * should be requested before the interrupt is exited.  How a context switch is
+ * requested from an ISR is dependent on the port - see the documentation page
+ * for the port in use.
+ *
+ * \defgroup xTaskNotifyWait xTaskNotifyWait
+ * \ingroup TaskNotifications
+ */
+void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * 
uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait );
+ * + * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this + * function to be available. + * + * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private + * "notification value", which is a 32-bit unsigned integer (uint32_t). + * + * Events can be sent to a task using an intermediary object. Examples of such + * objects are queues, semaphores, mutexes and event groups. Task notifications + * are a method of sending an event directly to a task without the need for such + * an intermediary object. + * + * A notification sent to a task can optionally perform an action, such as + * update, overwrite or increment the task's notification value. In that way + * task notifications can be used to send data to a task, or be used as light + * weight and fast binary or counting semaphores. + * + * ulTaskNotifyTake() is intended for use when a task notification is used as a + * faster and lighter weight binary or counting semaphore alternative. Actual + * FreeRTOS semaphores are taken using the xSemaphoreTake() API function, the + * equivalent action that instead uses a task notification is + * ulTaskNotifyTake(). + * + * When a task is using its notification value as a binary or counting semaphore + * other tasks should send notifications to it using the xTaskNotifyGive() + * macro, or xTaskNotify() function with the eAction parameter set to + * eIncrement. + * + * ulTaskNotifyTake() can either clear the task's notification value to + * zero on exit, in which case the notification value acts like a binary + * semaphore, or decrement the task's notification value on exit, in which case + * the notification value acts like a counting semaphore. + * + * A task can use ulTaskNotifyTake() to [optionally] block to wait for a + * the task's notification value to be non-zero. The task does not consume any + * CPU time while it is in the Blocked state. + * + * Where as xTaskNotifyWait() will return when a notification is pending, + * ulTaskNotifyTake() will return when the task's notification value is + * not zero. + * + * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details. + * + * @param xClearCountOnExit if xClearCountOnExit is pdFALSE then the task's + * notification value is decremented when the function exits. In this way the + * notification value acts like a counting semaphore. If xClearCountOnExit is + * not pdFALSE then the task's notification value is cleared to zero when the + * function exits. In this way the notification value acts like a binary + * semaphore. + * + * @param xTicksToWait The maximum amount of time that the task should wait in + * the Blocked state for the task's notification value to be greater than zero, + * should the count not already be greater than zero when + * ulTaskNotifyTake() was called. The task will not consume any processing + * time while it is in the Blocked state. This is specified in kernel ticks, + * the macro pdMS_TO_TICSK( value_in_ms ) can be used to convert a time + * specified in milliseconds to a time specified in ticks. + * + * @return The task's notification count before it is either cleared to zero or + * decremented (see the xClearCountOnExit parameter). + * + * \defgroup ulTaskNotifyTake ulTaskNotifyTake + * \ingroup TaskNotifications + */ +uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask );
+ * + * If the notification state of the task referenced by the handle xTask is + * eNotified, then set the task's notification state to eNotWaitingNotification. + * The task's notification value is not altered. Set xTask to NULL to clear the + * notification state of the calling task. + * + * @return pdTRUE if the task's notification state was set to + * eNotWaitingNotification, otherwise pdFALSE. + * \defgroup xTaskNotifyStateClear xTaskNotifyStateClear + * \ingroup TaskNotifications + */ +BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask ); + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. If a non-zero value is returned then a context switch is + * required because either: + * + A task was removed from a blocked list because its timeout had expired, + * or + * + Time slicing is in use and there is a task of equal priority to the + * currently running task. + */ +BaseType_t xTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * The 'unordered' version replaces the event list item value with the + * xItemValue value, and inserts the list item at the end of the list. + * + * The 'ordered' version uses the existing event list item value (which is the + * owning tasks priority) to insert the list item into the event list is task + * priority order. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xItemValue The item value to use for the event list item when the + * event list is not ordered by task priority. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_PERIOD_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; +void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + */ +void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList()/vTaskRemoveFromUnorderedEventList() will be called + * if either an event occurs to unblock a task, or the block timeout period + * expires. + * + * xTaskRemoveFromEventList() is used when the event list is in task priority + * order. It removes the list item from the head of the event list as that will + * have the highest priority owning task of all the tasks on the event list. + * vTaskRemoveFromUnorderedEventList() is used when the event list is not + * ordered and the event list items hold something other than the owning tasks + * priority. In this case the event list item value is updated to the value + * passed in the xItemValue parameter. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList ) PRIVILEGED_FUNCTION; +void vTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +portDONT_DISCARD void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * THESE FUNCTIONS MUST NOT BE USED FROM APPLICATION CODE. THEY ARE USED BY + * THE EVENT BITS MODULE. + */ +TickType_t uxTaskResetEventItemValue( void ) PRIVILEGED_FUNCTION; + +/* + * Return the id number of the running task + */ +unsigned portBASE_TYPE pxGetCurrentTaskNumber( void ) PRIVILEGED_FUNCTION; + +/* + * Return the priority of the running task + */ +unsigned portBASE_TYPE pxGetCurrentTaskPriority( void )PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +TaskHandle_t xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +BaseType_t xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +BaseType_t xTaskPriorityInherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * If a higher priority task attempting to obtain a mutex caused a lower + * priority task to inherit the higher priority task's priority - but the higher + * priority task then timed out without obtaining the mutex, then the lower + * priority task will disinherit the priority again - but only down as far as + * the highest priority task that is still waiting for the mutex (if there were + * more than one task waiting for the mutex). + */ +void vTaskPriorityDisinheritAfterTimeout( TaskHandle_t const pxMutexHolder, UBaseType_t uxHighestPriorityWaitingTask ) PRIVILEGED_FUNCTION; + +/* + * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. + */ +UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +/* + * Set the uxTaskNumber of the task referenced by the xTask parameter to + * uxHandle. + */ +void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle ) PRIVILEGED_FUNCTION; + +/* + * Only available when configUSE_TICKLESS_IDLE is set to 1. + * If tickless mode is being used, or a low power mode is implemented, then + * the tick interrupt will not execute during idle periods. When this is the + * case, the tick count value maintained by the scheduler needs to be kept up + * to date with the actual execution time by being skipped forward by a time + * equal to the idle period. + */ +void vTaskStepTick( const TickType_t xTicksToJump ) PRIVILEGED_FUNCTION; + +/* + * Only available when configUSE_TICKLESS_IDLE is set to 1. + * Provided for use within portSUPPRESS_TICKS_AND_SLEEP() to allow the port + * specific sleep function to determine if it is ok to proceed with the sleep, + * and if it is ok to proceed, if it is ok to sleep indefinitely. + * + * This function is necessary because portSUPPRESS_TICKS_AND_SLEEP() is only + * called with the scheduler suspended, not from within a critical section. It + * is therefore possible for an interrupt to request a context switch between + * portSUPPRESS_TICKS_AND_SLEEP() and the low power mode actually being + * entered. eTaskConfirmSleepModeStatus() should be called from a short + * critical section between the timer being stopped and the sleep mode being + * entered to ensure it is ok to proceed into the sleep mode. + */ +eSleepModeStatus eTaskConfirmSleepModeStatus( void ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Increment the mutex held count when a mutex is + * taken and return the handle of the task that has taken the mutex. + */ +TaskHandle_t pvTaskIncrementMutexHeldCount( void ) PRIVILEGED_FUNCTION; + +/* + * For internal use only. Same as vTaskSetTimeOutState(), but without a critial + * section. + */ +void vTaskInternalSetTimeOutState( TimeOut_t * const pxTimeOut ) PRIVILEGED_FUNCTION; + + +#ifdef __cplusplus +} +#endif +#endif /* INC_TASK_H */ + + + diff --git a/lib/FreeRTOS-SAMD51/src/tasks.c b/lib/FreeRTOS-SAMD51/src/tasks.c new file mode 100644 index 0000000..2abee0f --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/tasks.c @@ -0,0 +1,5236 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* Standard includes. */ +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "stack_macros.h" + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750 !e9021. */ + +/* Set configUSE_STATS_FORMATTING_FUNCTIONS to 2 to include the stats formatting +functions but without including stdio.h here. */ +#if ( configUSE_STATS_FORMATTING_FUNCTIONS == 1 ) + /* At the bottom of this file are two optional functions that can be used + to generate human readable text from the raw data generated by the + uxTaskGetSystemState() function. Note the formatting functions are provided + for convenience only, and are NOT considered part of the kernel. */ + #include +#endif /* configUSE_STATS_FORMATTING_FUNCTIONS == 1 ) */ + +#if( configUSE_PREEMPTION == 0 ) + /* If the cooperative scheduler is being used then a yield should not be + performed just because a higher priority task has been woken. */ + #define taskYIELD_IF_USING_PREEMPTION() +#else + #define taskYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API() +#endif + +/* Values that can be assigned to the ucNotifyState member of the TCB. */ +#define taskNOT_WAITING_NOTIFICATION ( ( uint8_t ) 0 ) +#define taskWAITING_NOTIFICATION ( ( uint8_t ) 1 ) +#define taskNOTIFICATION_RECEIVED ( ( uint8_t ) 2 ) + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* Bits used to recored how a task's stack and TCB were allocated. */ +#define tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB ( ( uint8_t ) 0 ) +#define tskSTATICALLY_ALLOCATED_STACK_ONLY ( ( uint8_t ) 1 ) +#define tskSTATICALLY_ALLOCATED_STACK_AND_TCB ( ( uint8_t ) 2 ) + +/* If any of the following are set then task stacks are filled with a known +value so the high water mark can be determined. If none of the following are +set then don't fill the stack so there is no unnecessary dependency on memset. */ +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) || ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + #define tskSET_NEW_STACKS_TO_KNOWN_VALUE 1 +#else + #define tskSET_NEW_STACKS_TO_KNOWN_VALUE 0 +#endif + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskRUNNING_CHAR ( 'X' ) +#define tskBLOCKED_CHAR ( 'B' ) +#define tskREADY_CHAR ( 'R' ) +#define tskDELETED_CHAR ( 'D' ) +#define tskSUSPENDED_CHAR ( 'S' ) + +/* + * Some kernel aware debuggers require the data the debugger needs access to be + * global, rather than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/* The name allocated to the Idle task. This can be overridden by defining +configIDLE_TASK_NAME in FreeRTOSConfig.h. */ +#ifndef configIDLE_TASK_NAME + #define configIDLE_TASK_NAME "IDLE" +#endif + +#if ( configUSE_PORT_OPTIMISED_TASK_SELECTION == 0 ) + + /* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 0 then task selection is + performed in a generic way that is not optimised to any particular + microcontroller architecture. */ + + /* uxTopReadyPriority holds the priority of the highest priority ready + state task. */ + #define taskRECORD_READY_PRIORITY( uxPriority ) \ + { \ + if( ( uxPriority ) > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( uxPriority ); \ + } \ + } /* taskRECORD_READY_PRIORITY */ + + /*-----------------------------------------------------------*/ + + #define taskSELECT_HIGHEST_PRIORITY_TASK() \ + { \ + UBaseType_t uxTopPriority = uxTopReadyPriority; \ + \ + /* Find the highest priority queue that contains ready tasks. */ \ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopPriority ] ) ) ) \ + { \ + configASSERT( uxTopPriority ); \ + --uxTopPriority; \ + } \ + \ + /* listGET_OWNER_OF_NEXT_ENTRY indexes through the list, so the tasks of \ + the same priority get an equal share of the processor time. */ \ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopPriority ] ) ); \ + uxTopReadyPriority = uxTopPriority; \ + } /* taskSELECT_HIGHEST_PRIORITY_TASK */ + + /*-----------------------------------------------------------*/ + + /* Define away taskRESET_READY_PRIORITY() and portRESET_READY_PRIORITY() as + they are only required when a port optimised method of task selection is + being used. */ + #define taskRESET_READY_PRIORITY( uxPriority ) + #define portRESET_READY_PRIORITY( uxPriority, uxTopReadyPriority ) + +#else /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ + + /* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 1 then task selection is + performed in a way that is tailored to the particular microcontroller + architecture being used. */ + + /* A port optimised version is provided. Call the port defined macros. */ + #define taskRECORD_READY_PRIORITY( uxPriority ) portRECORD_READY_PRIORITY( uxPriority, uxTopReadyPriority ) + + /*-----------------------------------------------------------*/ + + #define taskSELECT_HIGHEST_PRIORITY_TASK() \ + { \ + UBaseType_t uxTopPriority; \ + \ + /* Find the highest priority list that contains ready tasks. */ \ + portGET_HIGHEST_PRIORITY( uxTopPriority, uxTopReadyPriority ); \ + configASSERT( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ uxTopPriority ] ) ) > 0 ); \ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopPriority ] ) ); \ + } /* taskSELECT_HIGHEST_PRIORITY_TASK() */ + + /*-----------------------------------------------------------*/ + + /* A port optimised version is provided, call it only if the TCB being reset + is being referenced from a ready list. If it is referenced from a delayed + or suspended list then it won't be in a ready list. */ + #define taskRESET_READY_PRIORITY( uxPriority ) \ + { \ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ ( uxPriority ) ] ) ) == ( UBaseType_t ) 0 ) \ + { \ + portRESET_READY_PRIORITY( ( uxPriority ), ( uxTopReadyPriority ) ); \ + } \ + } + +#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ + +/*-----------------------------------------------------------*/ + +/* pxDelayedTaskList and pxOverflowDelayedTaskList are switched when the tick +count overflows. */ +#define taskSWITCH_DELAYED_LISTS() \ +{ \ + List_t *pxTemp; \ + \ + /* The delayed tasks list should be empty when the lists are switched. */ \ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); \ + \ + pxTemp = pxDelayedTaskList; \ + pxDelayedTaskList = pxOverflowDelayedTaskList; \ + pxOverflowDelayedTaskList = pxTemp; \ + xNumOfOverflows++; \ + prvResetNextTaskUnblockTime(); \ +} + +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready list for + * the task. It is inserted at the end of the list. + */ +#define prvAddTaskToReadyList( pxTCB ) \ + traceMOVED_TASK_TO_READY_STATE( pxTCB ); \ + taskRECORD_READY_PRIORITY( ( pxTCB )->uxPriority ); \ + vListInsertEnd( &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xStateListItem ) ); \ + tracePOST_MOVED_TASK_TO_READY_STATE( pxTCB ) +/*-----------------------------------------------------------*/ + +/* + * Several functions take an TaskHandle_t parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? pxCurrentTCB : ( pxHandle ) ) + +/* The item value of the event list item is normally used to hold the priority +of the task to which it belongs (coded to allow it to be held in reverse +priority order). However, it is occasionally borrowed for other purposes. It +is important its value is not updated due to a task priority change while it is +being used for another purpose. The following bit definition is used to inform +the scheduler that the value should not be changed - in which case it is the +responsibility of whichever module is using the value to ensure it gets set back +to its original value when it is released. */ +#if( configUSE_16_BIT_TICKS == 1 ) + #define taskEVENT_LIST_ITEM_VALUE_IN_USE 0x8000U +#else + #define taskEVENT_LIST_ITEM_VALUE_IN_USE 0x80000000UL +#endif + +/* + * Task control block. A task control block (TCB) is allocated for each task, + * and stores task state information, including a pointer to the task's context + * (the task's run time environment, including register values) + */ +typedef struct tskTaskControlBlock /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + volatile StackType_t *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE TCB STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE TCB STRUCT. */ + #endif + + ListItem_t xStateListItem; /*< The list that the state list item of a task is reference from denotes the state of that task (Ready, Blocked, Suspended ). */ + ListItem_t xEventListItem; /*< Used to reference a task from an event list. */ + UBaseType_t uxPriority; /*< The priority of the task. 0 is the lowest priority. */ + StackType_t *pxStack; /*< Points to the start of the stack. */ + char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + + #if ( ( portSTACK_GROWTH > 0 ) || ( configRECORD_STACK_HIGH_ADDRESS == 1 ) ) + StackType_t *pxEndOfStack; /*< Points to the highest valid address for the stack. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + UBaseType_t uxCriticalNesting; /*< Holds the critical section nesting depth for ports that do not maintain their own count in the port layer. */ + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxTCBNumber; /*< Stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ + UBaseType_t uxTaskNumber; /*< Stores a number specifically for use by third party trace code. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + UBaseType_t uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + UBaseType_t uxMutexesHeld; + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + TaskHookFunction_t pxTaskTag; + #endif + + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 ) + void *pvThreadLocalStoragePointers[ configNUM_THREAD_LOCAL_STORAGE_POINTERS ]; + #endif + + #if( configGENERATE_RUN_TIME_STATS == 1 ) + uint32_t ulRunTimeCounter; /*< Stores the amount of time the task has spent in the Running state. */ + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + /* Allocate a Newlib reent structure that is specific to this task. + Note Newlib support has been included by popular demand, but is not + used by the FreeRTOS maintainers themselves. FreeRTOS is not + responsible for resulting newlib operation. User must be familiar with + newlib and must provide system-wide implementations of the necessary + stubs. Be warned that (at the time of writing) the current newlib design + implements a system-wide malloc() that must be provided with locks. */ + struct _reent xNewLib_reent; + #endif + + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + volatile uint32_t ulNotifiedValue; + volatile uint8_t ucNotifyState; + #endif + + /* See the comments in FreeRTOS.h with the definition of + tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE. */ + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + uint8_t ucStaticallyAllocated; /*< Set to pdTRUE if the task is a statically allocated to ensure no attempt is made to free the memory. */ + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + uint8_t ucDelayAborted; + #endif + + #if( configUSE_POSIX_ERRNO == 1 ) + int iTaskErrno; + #endif + +} tskTCB; + +/* The old tskTCB name is maintained above then typedefed to the new TCB_t name +below to enable the use of older kernel aware debuggers. */ +typedef tskTCB TCB_t; + +/*lint -save -e956 A manual analysis and inspection has been used to determine +which static variables must be declared volatile. */ +PRIVILEGED_DATA TCB_t * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. -------------------- +xDelayedTaskList1 and xDelayedTaskList2 could be move to function scople but +doing so breaks some kernel aware debuggers and debuggers that rely on removing +the static qualifier. */ +PRIVILEGED_DATA static List_t pxReadyTasksLists[ configMAX_PRIORITIES ];/*< Prioritised ready tasks. */ +PRIVILEGED_DATA static List_t xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static List_t xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static List_t * volatile pxDelayedTaskList; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static List_t * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static List_t xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready list when the scheduler is resumed. */ + +#if( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static List_t xTasksWaitingTermination; /*< Tasks that have been deleted - but their memory not yet freed. */ + PRIVILEGED_DATA static volatile UBaseType_t uxDeletedTasksWaitingCleanUp = ( UBaseType_t ) 0U; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static List_t xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +/* Global POSIX errno. Its value is changed upon context switching to match +the errno of the currently running task. */ +#if ( configUSE_POSIX_ERRNO == 1 ) + int FreeRTOS_errno = 0; +#endif + +/* Other file private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile UBaseType_t uxCurrentNumberOfTasks = ( UBaseType_t ) 0U; +PRIVILEGED_DATA static volatile TickType_t xTickCount = ( TickType_t ) configINITIAL_TICK_COUNT; +PRIVILEGED_DATA static volatile UBaseType_t uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile BaseType_t xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile UBaseType_t uxPendedTicks = ( UBaseType_t ) 0U; +PRIVILEGED_DATA static volatile BaseType_t xYieldPending = pdFALSE; +PRIVILEGED_DATA static volatile BaseType_t xNumOfOverflows = ( BaseType_t ) 0; +PRIVILEGED_DATA static UBaseType_t uxTaskNumber = ( UBaseType_t ) 0U; +PRIVILEGED_DATA static volatile TickType_t xNextTaskUnblockTime = ( TickType_t ) 0U; /* Initialised to portMAX_DELAY before the scheduler starts. */ +PRIVILEGED_DATA static TaskHandle_t xIdleTaskHandle = NULL; /*< Holds the handle of the idle task. The idle task is created automatically when the scheduler is started. */ + +/* Context switches are held pending while the scheduler is suspended. Also, +interrupts must not manipulate the xStateListItem of a TCB, or any of the +lists the xStateListItem can be referenced from, if the scheduler is suspended. +If an interrupt needs to unblock a task while the scheduler is suspended then it +moves the task's event list item into the xPendingReadyList, ready for the +kernel to move the task from the pending ready list into the real ready list +when the scheduler is unsuspended. The pending ready list itself can only be +accessed from a critical section. */ +PRIVILEGED_DATA static volatile UBaseType_t uxSchedulerSuspended = ( UBaseType_t ) pdFALSE; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + /* Do not move these variables to function scope as doing so prevents the + code working with debuggers that need to remove the static qualifier. */ + PRIVILEGED_DATA static uint32_t ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + PRIVILEGED_DATA static uint32_t ulTotalRunTime = 0UL; /*< Holds the total amount of execution time as defined by the run time counter clock. */ + +#endif + +/*lint -restore */ + +/*-----------------------------------------------------------*/ + +/* Callback function prototypes. --------------------------*/ +#if( configCHECK_FOR_STACK_OVERFLOW > 0 ) + + extern void vApplicationStackOverflowHook( TaskHandle_t xTask, char *pcTaskName ); + +#endif + +#if( configUSE_TICK_HOOK > 0 ) + + extern void vApplicationTickHook( void ); /*lint !e526 Symbol not defined as it is an application callback. */ + +#endif + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + extern void vApplicationGetIdleTaskMemory( StaticTask_t **ppxIdleTaskTCBBuffer, StackType_t **ppxIdleTaskStackBuffer, uint32_t *pulIdleTaskStackSize ); /*lint !e526 Symbol not defined as it is an application callback. */ + +#endif + +/* File private functions. --------------------------------*/ + +/** + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + */ +#if ( INCLUDE_vTaskSuspend == 1 ) + + static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION; + +#endif /* INCLUDE_vTaskSuspend */ + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( TCB_t *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( TickType_t xTicksToWait, const BaseType_t xCanBlockIndefinitely ) PRIVILEGED_FUNCTION; + +/* + * Fills an TaskStatus_t structure with information on each task that is + * referenced from the pxList list (which may be a ready list, a delayed list, + * a suspended list, etc.). + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static UBaseType_t prvListTasksWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Searches pxList for a task with name pcNameToQuery - returning a handle to + * the task if it is found, or NULL if the task is not found. + */ +#if ( INCLUDE_xTaskGetHandle == 1 ) + + static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + + static configSTACK_DEPTH_TYPE prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Return the amount of time, in ticks, that will pass before the kernel will + * next move a task from the Blocked state to the Running state. + * + * This conditional compilation should use inequality to 0, not equality to 1. + * This is to ensure portSUPPRESS_TICKS_AND_SLEEP() can be called when user + * defined low power mode implementations require configUSE_TICKLESS_IDLE to be + * set to a value other than 1. + */ +#if ( configUSE_TICKLESS_IDLE != 0 ) + + static TickType_t prvGetExpectedIdleTime( void ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Set xNextTaskUnblockTime to the time at which the next Blocked state task + * will exit the Blocked state. + */ +static void prvResetNextTaskUnblockTime( void ); + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) + + /* + * Helper function used to pad task names with spaces when printing out + * human readable tables of task information. + */ + static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Called after a Task_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewTask( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask, + TCB_t *pxNewTCB, + const MemoryRegion_t * const xRegions ) PRIVILEGED_FUNCTION; + +/* + * Called after a new task has been created and initialised to place the task + * under the control of the scheduler. + */ +static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB ) PRIVILEGED_FUNCTION; + +/* + * freertos_tasks_c_additions_init() should only be called if the user definable + * macro FREERTOS_TASKS_C_ADDITIONS_INIT() is defined, as that is the only macro + * called by the function. + */ +#ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + + static void freertos_tasks_c_additions_init( void ) PRIVILEGED_FUNCTION; + +#endif + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + TaskHandle_t xTaskCreateStatic( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + StackType_t * const puxStackBuffer, + StaticTask_t * const pxTaskBuffer ) + { + TCB_t *pxNewTCB; + TaskHandle_t xReturn; + + configASSERT( puxStackBuffer != NULL ); + configASSERT( pxTaskBuffer != NULL ); + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticTask_t equals the size of the real task + structure. */ + volatile size_t xSize = sizeof( StaticTask_t ); + configASSERT( xSize == sizeof( TCB_t ) ); + ( void ) xSize; /* Prevent lint warning when configASSERT() is not used. */ + } + #endif /* configASSERT_DEFINED */ + + + if( ( pxTaskBuffer != NULL ) && ( puxStackBuffer != NULL ) ) + { + /* The memory used for the task's TCB and stack are passed into this + function - use them. */ + pxNewTCB = ( TCB_t * ) pxTaskBuffer; /*lint !e740 !e9087 Unusual cast is ok as the structures are designed to have the same alignment, and the size is checked by an assert. */ + pxNewTCB->pxStack = ( StackType_t * ) puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + { + /* Tasks can be created statically or dynamically, so note this + task was created statically in case the task is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskCode, pcName, ulStackDepth, pvParameters, uxPriority, &xReturn, pxNewTCB, NULL ); + prvAddNewTaskToReadyList( pxNewTCB ); + } + else + { + xReturn = NULL; + } + + return xReturn; + } + +#endif /* SUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) + + BaseType_t xTaskCreateRestrictedStatic( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + + configASSERT( pxTaskDefinition->puxStackBuffer != NULL ); + configASSERT( pxTaskDefinition->pxTaskBuffer != NULL ); + + if( ( pxTaskDefinition->puxStackBuffer != NULL ) && ( pxTaskDefinition->pxTaskBuffer != NULL ) ) + { + /* Allocate space for the TCB. Where the memory comes from depends + on the implementation of the port malloc function and whether or + not static allocation is being used. */ + pxNewTCB = ( TCB_t * ) pxTaskDefinition->pxTaskBuffer; + + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxTaskDefinition->puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + { + /* Tasks can be created statically or dynamically, so note this + task was created statically in case the task is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskDefinition->pvTaskCode, + pxTaskDefinition->pcName, + ( uint32_t ) pxTaskDefinition->usStackDepth, + pxTaskDefinition->pvParameters, + pxTaskDefinition->uxPriority, + pxCreatedTask, pxNewTCB, + pxTaskDefinition->xRegions ); + + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + + return xReturn; + } + +#endif /* ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( portUSING_MPU_WRAPPERS == 1 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + BaseType_t xTaskCreateRestricted( const TaskParameters_t * const pxTaskDefinition, TaskHandle_t *pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + + configASSERT( pxTaskDefinition->puxStackBuffer ); + + if( pxTaskDefinition->puxStackBuffer != NULL ) + { + /* Allocate space for the TCB. Where the memory comes from depends + on the implementation of the port malloc function and whether or + not static allocation is being used. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); + + if( pxNewTCB != NULL ) + { + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxTaskDefinition->puxStackBuffer; + + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) + { + /* Tasks can be created statically or dynamically, so note + this task had a statically allocated stack in case it is + later deleted. The TCB was allocated dynamically. */ + pxNewTCB->ucStaticallyAllocated = tskSTATICALLY_ALLOCATED_STACK_ONLY; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskDefinition->pvTaskCode, + pxTaskDefinition->pcName, + ( uint32_t ) pxTaskDefinition->usStackDepth, + pxTaskDefinition->pvParameters, + pxTaskDefinition->uxPriority, + pxCreatedTask, pxNewTCB, + pxTaskDefinition->xRegions ); + + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + } + + return xReturn; + } + +#endif /* portUSING_MPU_WRAPPERS */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + BaseType_t xTaskCreate( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const configSTACK_DEPTH_TYPE usStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask ) + { + TCB_t *pxNewTCB; + BaseType_t xReturn; + + /* If the stack grows down then allocate the stack then the TCB so the stack + does not grow into the TCB. Likewise if the stack grows up then allocate + the TCB then the stack. */ + #if( portSTACK_GROWTH > 0 ) + { + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function and whether or not static + allocation is being used. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( StackType_t * ) pvPortMalloc( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + } + } + #else /* portSTACK_GROWTH */ + { + StackType_t *pxStack; + + /* Allocate space for the stack used by the task being created. */ + pxStack = pvPortMalloc( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation is the stack. */ + + if( pxStack != NULL ) + { + /* Allocate space for the TCB. */ + pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) ); /*lint !e9087 !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack, and the first member of TCB_t is always a pointer to the task's stack. */ + + if( pxNewTCB != NULL ) + { + /* Store the stack location in the TCB. */ + pxNewTCB->pxStack = pxStack; + } + else + { + /* The stack cannot be used as the TCB was not created. Free + it again. */ + vPortFree( pxStack ); + } + } + else + { + pxNewTCB = NULL; + } + } + #endif /* portSTACK_GROWTH */ + + if( pxNewTCB != NULL ) + { + #if( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e9029 !e731 Macro has been consolidated for readability reasons. */ + { + /* Tasks can be created statically or dynamically, so note this + task was created dynamically in case it is later deleted. */ + pxNewTCB->ucStaticallyAllocated = tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB; + } + #endif /* tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE */ + + prvInitialiseNewTask( pxTaskCode, pcName, ( uint32_t ) usStackDepth, pvParameters, uxPriority, pxCreatedTask, pxNewTCB, NULL ); + prvAddNewTaskToReadyList( pxNewTCB ); + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewTask( TaskFunction_t pxTaskCode, + const char * const pcName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const uint32_t ulStackDepth, + void * const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t * const pxCreatedTask, + TCB_t *pxNewTCB, + const MemoryRegion_t * const xRegions ) +{ +StackType_t *pxTopOfStack; +UBaseType_t x; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + BaseType_t xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Avoid dependency on memset() if it is not required. */ + #if( tskSET_NEW_STACKS_TO_KNOWN_VALUE == 1 ) + { + /* Fill the stack with a known value to assist debugging. */ + ( void ) memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) ulStackDepth * sizeof( StackType_t ) ); + } + #endif /* tskSET_NEW_STACKS_TO_KNOWN_VALUE */ + + /* Calculate the top of stack address. This depends on whether the stack + grows from high memory to low (as per the 80x86) or vice versa. + portSTACK_GROWTH is used to make the result positive or negative as required + by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = &( pxNewTCB->pxStack[ ulStackDepth - ( uint32_t ) 1 ] ); + pxTopOfStack = ( StackType_t * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); /*lint !e923 !e9033 !e9078 MISRA exception. Avoiding casts between pointers and integers is not practical. Size differences accounted for using portPOINTER_SIZE_TYPE type. Checked by assert(). */ + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + #if( configRECORD_STACK_HIGH_ADDRESS == 1 ) + { + /* Also record the stack's high address, which may assist + debugging. */ + pxNewTCB->pxEndOfStack = pxTopOfStack; + } + #endif /* configRECORD_STACK_HIGH_ADDRESS */ + } + #else /* portSTACK_GROWTH */ + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxNewTCB->pxStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* The other extreme of the stack space is required if stack checking is + performed. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( ulStackDepth - ( uint32_t ) 1 ); + } + #endif /* portSTACK_GROWTH */ + + /* Store the task name in the TCB. */ + if( pcName != NULL ) + { + for( x = ( UBaseType_t ) 0; x < ( UBaseType_t ) configMAX_TASK_NAME_LEN; x++ ) + { + pxNewTCB->pcTaskName[ x ] = pcName[ x ]; + + /* Don't copy all configMAX_TASK_NAME_LEN if the string is shorter than + configMAX_TASK_NAME_LEN characters just in case the memory after the + string is not accessible (extremely unlikely). */ + if( pcName[ x ] == ( char ) 0x00 ) + { + break; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Ensure the name string is terminated in the case that the string length + was greater or equal to configMAX_TASK_NAME_LEN. */ + pxNewTCB->pcTaskName[ configMAX_TASK_NAME_LEN - 1 ] = '\0'; + } + else + { + /* The task has not been given a name, so just ensure there is a NULL + terminator when it is read out. */ + pxNewTCB->pcTaskName[ 0 ] = 0x00; + } + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= ( UBaseType_t ) configMAX_PRIORITIES ) + { + uxPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxNewTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxNewTCB->uxBasePriority = uxPriority; + pxNewTCB->uxMutexesHeld = 0; + } + #endif /* configUSE_MUTEXES */ + + vListInitialiseItem( &( pxNewTCB->xStateListItem ) ); + vListInitialiseItem( &( pxNewTCB->xEventListItem ) ); + + /* Set the pxNewTCB as a link back from the ListItem_t. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxNewTCB->xStateListItem ), pxNewTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxNewTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + listSET_LIST_ITEM_OWNER( &( pxNewTCB->xEventListItem ), pxNewTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxNewTCB->uxCriticalNesting = ( UBaseType_t ) 0U; + } + #endif /* portCRITICAL_NESTING_IN_TCB */ + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxNewTCB->pxTaskTag = NULL; + } + #endif /* configUSE_APPLICATION_TASK_TAG */ + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxNewTCB->ulRunTimeCounter = 0UL; + } + #endif /* configGENERATE_RUN_TIME_STATS */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxNewTCB->xMPUSettings ), xRegions, pxNewTCB->pxStack, ulStackDepth ); + } + #else + { + /* Avoid compiler warning about unreferenced parameter. */ + ( void ) xRegions; + } + #endif + + #if( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + { + for( x = 0; x < ( UBaseType_t ) configNUM_THREAD_LOCAL_STORAGE_POINTERS; x++ ) + { + pxNewTCB->pvThreadLocalStoragePointers[ x ] = NULL; + } + } + #endif + + #if ( configUSE_TASK_NOTIFICATIONS == 1 ) + { + pxNewTCB->ulNotifiedValue = 0; + pxNewTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Initialise this task's Newlib reent structure. */ + _REENT_INIT_PTR( ( &( pxNewTCB->xNewLib_reent ) ) ); + } + #endif + + #if( INCLUDE_xTaskAbortDelay == 1 ) + { + pxNewTCB->ucDelayAborted = pdFALSE; + } + #endif + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + /* If the port has capability to detect stack overflow, + pass the stack end address to the stack initialization + function as well. */ + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + { + #if( portSTACK_GROWTH < 0 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else /* portSTACK_GROWTH */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxEndOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #endif /* portSTACK_GROWTH */ + } + #else /* portHAS_STACK_OVERFLOW_CHECKING */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #endif /* portHAS_STACK_OVERFLOW_CHECKING */ + } + #else /* portUSING_MPU_WRAPPERS */ + { + /* If the port has capability to detect stack overflow, + pass the stack end address to the stack initialization + function as well. */ + #if( portHAS_STACK_OVERFLOW_CHECKING == 1 ) + { + #if( portSTACK_GROWTH < 0 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxStack, pxTaskCode, pvParameters ); + } + #else /* portSTACK_GROWTH */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxNewTCB->pxEndOfStack, pxTaskCode, pvParameters ); + } + #endif /* portSTACK_GROWTH */ + } + #else /* portHAS_STACK_OVERFLOW_CHECKING */ + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif /* portHAS_STACK_OVERFLOW_CHECKING */ + } + #endif /* portUSING_MPU_WRAPPERS */ + + if( pxCreatedTask != NULL ) + { + /* Pass the handle out in an anonymous way. The handle can be used to + change the created task's priority, delete the created task, etc.*/ + *pxCreatedTask = ( TaskHandle_t ) pxNewTCB; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB ) +{ + /* Ensure interrupts don't access the task lists while the lists are being + updated. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( UBaseType_t ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= pxNewTCB->uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + uxTaskNumber++; + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif /* configUSE_TRACE_FACILITY */ + traceTASK_CREATE( pxNewTCB ); + + prvAddTaskToReadyList( pxNewTCB ); + + portSETUP_TCB( pxNewTCB ); + } + taskEXIT_CRITICAL(); + + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < pxNewTCB->uxPriority ) + { + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( TaskHandle_t xTaskToDelete ) + { + TCB_t *pxTCB; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the calling task that is + being deleted. */ + pxTCB = prvGetTCBFromHandle( xTaskToDelete ); + + /* Remove task from the ready list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Is the task waiting on an event also? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Increment the uxTaskNumber also so kernel aware debuggers can + detect that the task lists need re-generating. This is done before + portPRE_TASK_DELETE_HOOK() as in the Windows port that macro will + not return. */ + uxTaskNumber++; + + if( pxTCB == pxCurrentTCB ) + { + /* A task is deleting itself. This cannot complete within the + task itself, as a context switch to another task is required. + Place the task in the termination list. The idle task will + check the termination list and free up any memory allocated by + the scheduler for the TCB and stack of the deleted task. */ + vListInsertEnd( &xTasksWaitingTermination, &( pxTCB->xStateListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxDeletedTasksWaitingCleanUp; + + /* The pre-delete hook is primarily for the Windows simulator, + in which Windows specific clean up operations are performed, + after which it is not possible to yield away from this task - + hence xYieldPending is used to latch that a context switch is + required. */ + portPRE_TASK_DELETE_HOOK( pxTCB, &xYieldPending ); + } + else + { + --uxCurrentNumberOfTasks; + prvDeleteTCB( pxTCB ); + + /* Reset the next expected unblock time in case it referred to + the task that has just been deleted. */ + prvResetNextTaskUnblockTime(); + } + + traceTASK_DELETE( pxTCB ); + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if it is the currently running task that has just + been deleted. */ + if( xSchedulerRunning != pdFALSE ) + { + if( pxTCB == pxCurrentTCB ) + { + configASSERT( uxSchedulerSuspended == 0 ); + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + +#endif /* INCLUDE_vTaskDelete */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) + { + TickType_t xTimeToWake; + BaseType_t xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0U ) ); + configASSERT( uxSchedulerSuspended == 0 ); + + vTaskSuspendAll(); + { + /* Minor optimisation. The tick count cannot change in this + block. */ + const TickType_t xConstTickCount = xTickCount; + + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xConstTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xConstTickCount ) ) + { + xShouldDelay = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xConstTickCount ) ) + { + xShouldDelay = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL( xTimeToWake ); + + /* prvAddCurrentTaskToDelayedList() needs the block time, not + the time to wake, so subtract the current tick count. */ + prvAddCurrentTaskToDelayedList( xTimeToWake - xConstTickCount, pdFALSE ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskDelayUntil */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( const TickType_t xTicksToDelay ) + { + BaseType_t xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( TickType_t ) 0U ) + { + configASSERT( uxSchedulerSuspended == 0 ); + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + prvAddCurrentTaskToDelayedList( xTicksToDelay, pdFALSE ); + } + xAlreadyYielded = xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskDelay */ +/*-----------------------------------------------------------*/ + +#if( ( INCLUDE_eTaskGetState == 1 ) || ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_xTaskAbortDelay == 1 ) ) + + eTaskState eTaskGetState( TaskHandle_t xTask ) + { + eTaskState eReturn; + List_t const * pxStateList, *pxDelayedList, *pxOverflowedDelayedList; + const TCB_t * const pxTCB = xTask; + + configASSERT( pxTCB ); + + if( pxTCB == pxCurrentTCB ) + { + /* The task calling this function is querying its own state. */ + eReturn = eRunning; + } + else + { + taskENTER_CRITICAL(); + { + pxStateList = listLIST_ITEM_CONTAINER( &( pxTCB->xStateListItem ) ); + pxDelayedList = pxDelayedTaskList; + pxOverflowedDelayedList = pxOverflowDelayedTaskList; + } + taskEXIT_CRITICAL(); + + if( ( pxStateList == pxDelayedList ) || ( pxStateList == pxOverflowedDelayedList ) ) + { + /* The task being queried is referenced from one of the Blocked + lists. */ + eReturn = eBlocked; + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + else if( pxStateList == &xSuspendedTaskList ) + { + /* The task being queried is referenced from the suspended + list. Is it genuinely suspended or is it blocked + indefinitely? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ) + { + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + { + /* The task does not appear on the event list item of + and of the RTOS objects, but could still be in the + blocked state if it is waiting on its notification + rather than waiting on an object. */ + if( pxTCB->ucNotifyState == taskWAITING_NOTIFICATION ) + { + eReturn = eBlocked; + } + else + { + eReturn = eSuspended; + } + } + #else + { + eReturn = eSuspended; + } + #endif + } + else + { + eReturn = eBlocked; + } + } + #endif + + #if ( INCLUDE_vTaskDelete == 1 ) + else if( ( pxStateList == &xTasksWaitingTermination ) || ( pxStateList == NULL ) ) + { + /* The task being queried is referenced from the deleted + tasks list, or it is not referenced from any lists at + all. */ + eReturn = eDeleted; + } + #endif + + else /*lint !e525 Negative indentation is intended to make use of pre-processor clearer. */ + { + /* If the task is not in any other state, it must be in the + Ready (including pending ready) state. */ + eReturn = eReady; + } + } + + return eReturn; + } /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */ + +#endif /* INCLUDE_eTaskGetState */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + UBaseType_t uxTaskPriorityGet( const TaskHandle_t xTask ) + { + TCB_t const *pxTCB; + UBaseType_t uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the priority of the task + that called uxTaskPriorityGet() that is being queried. */ + pxTCB = prvGetTCBFromHandle( xTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskPriorityGet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + UBaseType_t uxTaskPriorityGetFromISR( const TaskHandle_t xTask ) + { + TCB_t const *pxTCB; + UBaseType_t uxReturn, uxSavedInterruptState; + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptState = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* If null is passed in here then it is the priority of the calling + task that is being queried. */ + pxTCB = prvGetTCBFromHandle( xTask ); + uxReturn = pxTCB->uxPriority; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptState ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskPriorityGet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) + { + TCB_t *pxTCB; + UBaseType_t uxCurrentBasePriority, uxPriorityUsedOnEntry; + BaseType_t xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= ( UBaseType_t ) configMAX_PRIORITIES ) + { + uxNewPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the priority of the calling + task that is being changed. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentBasePriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentBasePriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentBasePriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentBasePriority ) + { + if( pxTCB != pxCurrentTCB ) + { + /* The priority of a task other than the currently + running task is being raised. Is the priority being + raised above that of the running task? */ + if( uxNewPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + /* The priority of the running task is being raised, + but the running task must already be the highest + priority task able to run so no yield is required. */ + } + } + else if( pxTCB == pxCurrentTCB ) + { + /* Setting the priority of the running task down means + there may now be another task of higher priority that + is ready to execute. */ + xYieldRequired = pdTRUE; + } + else + { + /* Setting the priority of any other task down does not + require a yield as the running task must be above the + new priority of the task being modified. */ + } + + /* Remember the ready list the task might be referenced from + before its uxPriority member is changed so the + taskRESET_READY_PRIORITY() macro can function correctly. */ + uxPriorityUsedOnEntry = pxTCB->uxPriority; + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + /* Only reset the event list item value if the value is not + being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxNewPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the task is in the blocked or suspended list we need do + nothing more than change its priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the list appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxPriorityUsedOnEntry ] ), &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + /* The task is currently in its ready list - remove before + adding it to it's new ready list. As we are in a critical + section we can do this even if the scheduler is suspended. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* It is known that the task is in its ready list so + there is no need to check again and the port level + reset macro can be called directly. */ + portRESET_READY_PRIORITY( uxPriorityUsedOnEntry, uxTopReadyPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + prvAddTaskToReadyList( pxTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xYieldRequired != pdFALSE ) + { + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Remove compiler warning about unused variables when the port + optimised task selection is not being used. */ + ( void ) uxPriorityUsedOnEntry; + } + } + taskEXIT_CRITICAL(); + } + +#endif /* INCLUDE_vTaskPrioritySet */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( TaskHandle_t xTaskToSuspend ) + { + TCB_t *pxTCB; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then it is the running task that is + being suspended. */ + pxTCB = prvGetTCBFromHandle( xTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the + suspended list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Is the task waiting on an event also? */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + vListInsertEnd( &xSuspendedTaskList, &( pxTCB->xStateListItem ) ); + + #if( configUSE_TASK_NOTIFICATIONS == 1 ) + { + if( pxTCB->ucNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task was blocked to wait for a notification, but is + now suspended, so no notification was received. */ + pxTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + } + #endif + } + taskEXIT_CRITICAL(); + + if( xSchedulerRunning != pdFALSE ) + { + /* Reset the next expected unblock time in case it referred to the + task that is now in the Suspended state. */ + taskENTER_CRITICAL(); + { + prvResetNextTaskUnblockTime(); + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( pxTCB == pxCurrentTCB ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* The current task has just been suspended. */ + configASSERT( uxSchedulerSuspended == 0 ); + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) /*lint !e931 Right has no side effect, just volatile. */ + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskSuspend */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask ) + { + BaseType_t xReturn = pdFALSE; + const TCB_t * const pxTCB = xTask; + + /* Accesses xPendingReadyList so must be called from a critical + section. */ + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task being resumed actually in the suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) == pdFALSE ) + { + /* Is it in the suspended list because it is in the Suspended + state, or because is is blocked with no timeout? */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) != pdFALSE ) /*lint !e961. The cast is only redundant when NULL is used. */ + { + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */ + +#endif /* INCLUDE_vTaskSuspend */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( TaskHandle_t xTaskToResume ) + { + TCB_t * const pxTCB = xTaskToResume; + + /* It does not make sense to resume the calling task. */ + configASSERT( xTaskToResume ); + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != pxCurrentTCB ) && ( pxTCB != NULL ) ) + { + taskENTER_CRITICAL(); + { + if( prvTaskIsTaskSuspended( pxTCB ) != pdFALSE ) + { + traceTASK_RESUME( pxTCB ); + + /* The ready list can be accessed even if the scheduler is + suspended because this is inside a critical section. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* A higher priority task may have just been resumed. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, + but will leave the lists in the correct state for the + next yield. */ + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* INCLUDE_vTaskSuspend */ + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume ) + { + BaseType_t xYieldRequired = pdFALSE; + TCB_t * const pxTCB = xTaskToResume; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToResume ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( prvTaskIsTaskSuspended( pxTCB ) != pdFALSE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + /* Check the ready lists can be accessed. */ + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + /* Ready lists can be accessed so move the task from the + suspended list to the ready list directly. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed or ready lists cannot be accessed so the task + is held in the pending ready list until the scheduler is + unsuspended. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xYieldRequired; + } + +#endif /* ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) */ +/*-----------------------------------------------------------*/ + +void vTaskStartScheduler( void ) +{ +BaseType_t xReturn; + + /* Add the idle task at the lowest priority. */ + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + StaticTask_t *pxIdleTaskTCBBuffer = NULL; + StackType_t *pxIdleTaskStackBuffer = NULL; + uint32_t ulIdleTaskStackSize; + + /* The Idle task is created using user provided RAM - obtain the + address of the RAM then create the idle task. */ + vApplicationGetIdleTaskMemory( &pxIdleTaskTCBBuffer, &pxIdleTaskStackBuffer, &ulIdleTaskStackSize ); + xIdleTaskHandle = xTaskCreateStatic( prvIdleTask, + configIDLE_TASK_NAME, + ulIdleTaskStackSize, + ( void * ) NULL, /*lint !e961. The cast is not redundant for all compilers. */ + portPRIVILEGE_BIT, /* In effect ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), but tskIDLE_PRIORITY is zero. */ + pxIdleTaskStackBuffer, + pxIdleTaskTCBBuffer ); /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */ + + if( xIdleTaskHandle != NULL ) + { + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + } + #else + { + /* The Idle task is being created using dynamically allocated RAM. */ + xReturn = xTaskCreate( prvIdleTask, + configIDLE_TASK_NAME, + configMINIMAL_STACK_SIZE, + ( void * ) NULL, + portPRIVILEGE_BIT, /* In effect ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), but tskIDLE_PRIORITY is zero. */ + &xIdleTaskHandle ); /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */ + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TIMERS */ + + if( xReturn == pdPASS ) + { + /* freertos_tasks_c_additions_init() should only be called if the user + definable macro FREERTOS_TASKS_C_ADDITIONS_INIT() is defined, as that is + the only macro called by the function. */ + #ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + { + freertos_tasks_c_additions_init(); + } + #endif + + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. */ + portDISABLE_INTERRUPTS(); + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Switch Newlib's _impure_ptr variable to point to the _reent + structure specific to the task that will run first. */ + _impure_ptr = &( pxCurrentTCB->xNewLib_reent ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + + xNextTaskUnblockTime = portMAX_DELAY; + xSchedulerRunning = pdTRUE; + xTickCount = ( TickType_t ) configINITIAL_TICK_COUNT; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. NOTE: If configGENERATE_RUN_TIME_STATS + is set to 0 and the following line fails to build then ensure you do not + have portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() defined in your + FreeRTOSConfig.h file. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + traceTASK_SWITCHED_IN(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() != pdFALSE ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + else + { + /* This line will only be reached if the kernel could not be started, + because there was not enough FreeRTOS heap to create the idle task + or the timer task. */ + configASSERT( xReturn != errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ); + } + + /* Prevent compiler warnings if INCLUDE_xTaskGetIdleTaskHandle is set to 0, + meaning xIdleTaskHandle is not used anywhere else. */ + ( void ) xIdleTaskHandle; +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + BaseType_t. Please read Richard Barry's reply in the following link to a + post in the FreeRTOS support forum before reporting this as a bug! - + http://goo.gl/wu4acr */ + ++uxSchedulerSuspended; + portMEMORY_BARRIER(); +} +/*----------------------------------------------------------*/ + +#if ( configUSE_TICKLESS_IDLE != 0 ) + + static TickType_t prvGetExpectedIdleTime( void ) + { + TickType_t xReturn; + UBaseType_t uxHigherPriorityReadyTasks = pdFALSE; + + /* uxHigherPriorityReadyTasks takes care of the case where + configUSE_PREEMPTION is 0, so there may be tasks above the idle priority + task that are in the Ready state, even though the idle task is + running. */ + #if( configUSE_PORT_OPTIMISED_TASK_SELECTION == 0 ) + { + if( uxTopReadyPriority > tskIDLE_PRIORITY ) + { + uxHigherPriorityReadyTasks = pdTRUE; + } + } + #else + { + const UBaseType_t uxLeastSignificantBit = ( UBaseType_t ) 0x01; + + /* When port optimised task selection is used the uxTopReadyPriority + variable is used as a bit map. If bits other than the least + significant bit are set then there are tasks that have a priority + above the idle priority that are in the Ready state. This takes + care of the case where the co-operative scheduler is in use. */ + if( uxTopReadyPriority > uxLeastSignificantBit ) + { + uxHigherPriorityReadyTasks = pdTRUE; + } + } + #endif + + if( pxCurrentTCB->uxPriority > tskIDLE_PRIORITY ) + { + xReturn = 0; + } + else if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > 1 ) + { + /* There are other idle priority tasks in the ready state. If + time slicing is used then the very next tick interrupt must be + processed. */ + xReturn = 0; + } + else if( uxHigherPriorityReadyTasks != pdFALSE ) + { + /* There are tasks in the Ready state that have a priority above the + idle priority. This path can only be reached if + configUSE_PREEMPTION is 0. */ + xReturn = 0; + } + else + { + xReturn = xNextTaskUnblockTime - xTickCount; + } + + return xReturn; + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*----------------------------------------------------------*/ + +BaseType_t xTaskResumeAll( void ) +{ +TCB_t *pxTCB = NULL; +BaseType_t xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( UBaseType_t ) 0U ) + { + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( &xPendingReadyList ) == pdFALSE ) + { + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( ( &xPendingReadyList ) ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* If the moved task has a priority higher than the current + task then a yield must be performed. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + if( pxTCB != NULL ) + { + /* A task was unblocked while the scheduler was suspended, + which may have prevented the next unblock time from being + re-calculated, in which case re-calculate it now. Mainly + important for low power tickless implementations, where + this can prevent an unnecessary exit from low power + state. */ + prvResetNextTaskUnblockTime(); + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does + not slip, and that any delayed tasks are resumed at the correct + time. */ + { + UBaseType_t uxPendedCounts = uxPendedTicks; /* Non-volatile copy. */ + + if( uxPendedCounts > ( UBaseType_t ) 0U ) + { + do + { + if( xTaskIncrementTick() != pdFALSE ) + { + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + --uxPendedCounts; + } while( uxPendedCounts > ( UBaseType_t ) 0U ); + + uxPendedTicks = 0; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + if( xYieldPending != pdFALSE ) + { + #if( configUSE_PREEMPTION != 0 ) + { + xAlreadyYielded = pdTRUE; + } + #endif + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} +/*-----------------------------------------------------------*/ + +TickType_t xTaskGetTickCount( void ) +{ +TickType_t xTicks; + + /* Critical section required if running on a 16 bit processor. */ + portTICK_TYPE_ENTER_CRITICAL(); + { + xTicks = xTickCount; + } + portTICK_TYPE_EXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +TickType_t xTaskGetTickCountFromISR( void ) +{ +TickType_t xReturn; +UBaseType_t uxSavedInterruptStatus; + + /* RTOS ports that support interrupt nesting have the concept of a maximum + system call (or maximum API call) interrupt priority. Interrupts that are + above the maximum system call priority are kept permanently enabled, even + when the RTOS kernel is in a critical section, but cannot make any calls to + FreeRTOS API functions. If configASSERT() is defined in FreeRTOSConfig.h + then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has been + assigned a priority above the configured maximum system call priority. + Only FreeRTOS functions that end in FromISR can be called from interrupts + that have been assigned a priority at or (logically) below the maximum + system call interrupt priority. FreeRTOS maintains a separate interrupt + safe API to ensure interrupt entry is as fast and as simple as possible. + More information (albeit Cortex-M specific) is provided on the following + link: https://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + uxSavedInterruptStatus = portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR(); + { + xReturn = xTickCount; + } + portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +UBaseType_t uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + BaseType_t. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +char *pcTaskGetName( TaskHandle_t xTaskToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +{ +TCB_t *pxTCB; + + /* If null is passed in here then the name of the calling task is being + queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetHandle == 1 ) + + static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] ) + { + TCB_t *pxNextTCB, *pxFirstTCB, *pxReturn = NULL; + UBaseType_t x; + char cNextChar; + BaseType_t xBreakLoop; + + /* This function is called with the scheduler suspended. */ + + if( listCURRENT_LIST_LENGTH( pxList ) > ( UBaseType_t ) 0 ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Check each character in the name looking for a match or + mismatch. */ + xBreakLoop = pdFALSE; + for( x = ( UBaseType_t ) 0; x < ( UBaseType_t ) configMAX_TASK_NAME_LEN; x++ ) + { + cNextChar = pxNextTCB->pcTaskName[ x ]; + + if( cNextChar != pcNameToQuery[ x ] ) + { + /* Characters didn't match. */ + xBreakLoop = pdTRUE; + } + else if( cNextChar == ( char ) 0x00 ) + { + /* Both strings terminated, a match must have been + found. */ + pxReturn = pxNextTCB; + xBreakLoop = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + if( xBreakLoop != pdFALSE ) + { + break; + } + } + + if( pxReturn != NULL ) + { + /* The handle has been found. */ + break; + } + + } while( pxNextTCB != pxFirstTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return pxReturn; + } + +#endif /* INCLUDE_xTaskGetHandle */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetHandle == 1 ) + + TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + { + UBaseType_t uxQueue = configMAX_PRIORITIES; + TCB_t* pxTCB; + + /* Task names will be truncated to configMAX_TASK_NAME_LEN - 1 bytes. */ + configASSERT( strlen( pcNameToQuery ) < configMAX_TASK_NAME_LEN ); + + vTaskSuspendAll(); + { + /* Search the ready lists. */ + do + { + uxQueue--; + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) &( pxReadyTasksLists[ uxQueue ] ), pcNameToQuery ); + + if( pxTCB != NULL ) + { + /* Found the handle. */ + break; + } + + } while( uxQueue > ( UBaseType_t ) tskIDLE_PRIORITY ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + /* Search the delayed lists. */ + if( pxTCB == NULL ) + { + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) pxDelayedTaskList, pcNameToQuery ); + } + + if( pxTCB == NULL ) + { + pxTCB = prvSearchForNameWithinSingleList( ( List_t * ) pxOverflowDelayedTaskList, pcNameToQuery ); + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( pxTCB == NULL ) + { + /* Search the suspended list. */ + pxTCB = prvSearchForNameWithinSingleList( &xSuspendedTaskList, pcNameToQuery ); + } + } + #endif + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( pxTCB == NULL ) + { + /* Search the deleted list. */ + pxTCB = prvSearchForNameWithinSingleList( &xTasksWaitingTermination, pcNameToQuery ); + } + } + #endif + } + ( void ) xTaskResumeAll(); + + return pxTCB; + } + +#endif /* INCLUDE_xTaskGetHandle */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) + { + UBaseType_t uxTask = 0, uxQueue = configMAX_PRIORITIES; + + vTaskSuspendAll(); + { + /* Is there a space in the array for each task in the system? */ + if( uxArraySize >= uxCurrentNumberOfTasks ) + { + /* Fill in an TaskStatus_t structure with information on each + task in the Ready state. */ + do + { + uxQueue--; + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &( pxReadyTasksLists[ uxQueue ] ), eReady ); + + } while( uxQueue > ( UBaseType_t ) tskIDLE_PRIORITY ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + /* Fill in an TaskStatus_t structure with information on each + task in the Blocked state. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxDelayedTaskList, eBlocked ); + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxOverflowDelayedTaskList, eBlocked ); + + #if( INCLUDE_vTaskDelete == 1 ) + { + /* Fill in an TaskStatus_t structure with information on + each task that has been deleted but not yet cleaned up. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xTasksWaitingTermination, eDeleted ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + /* Fill in an TaskStatus_t structure with information on + each task in the Suspended state. */ + uxTask += prvListTasksWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xSuspendedTaskList, eSuspended ); + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1) + { + if( pulTotalRunTime != NULL ) + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ( *pulTotalRunTime ) ); + #else + *pulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + } + } + #else + { + if( pulTotalRunTime != NULL ) + { + *pulTotalRunTime = 0; + } + } + #endif + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + ( void ) xTaskResumeAll(); + + return uxTask; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + TaskHandle_t xTaskGetIdleTaskHandle( void ) + { + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; + } + +#endif /* INCLUDE_xTaskGetIdleTaskHandle */ +/*----------------------------------------------------------*/ + +/* This conditional compilation should use inequality to 0, not equality to 1. +This is to ensure vTaskStepTick() is available when user defined low power mode +implementations require configUSE_TICKLESS_IDLE to be set to a value other than +1. */ +#if ( configUSE_TICKLESS_IDLE != 0 ) + + void vTaskStepTick( const TickType_t xTicksToJump ) + { + /* Correct the tick count value after a period during which the tick + was suppressed. Note this does *not* call the tick hook function for + each stepped tick. */ + configASSERT( ( xTickCount + xTicksToJump ) <= xNextTaskUnblockTime ); + xTickCount += xTicksToJump; + traceINCREASE_TICK_COUNT( xTicksToJump ); + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskAbortDelay == 1 ) + + BaseType_t xTaskAbortDelay( TaskHandle_t xTask ) + { + TCB_t *pxTCB = xTask; + BaseType_t xReturn; + + configASSERT( pxTCB ); + + vTaskSuspendAll(); + { + /* A task can only be prematurely removed from the Blocked state if + it is actually in the Blocked state. */ + if( eTaskGetState( xTask ) == eBlocked ) + { + xReturn = pdPASS; + + /* Remove the reference to the task from the blocked list. An + interrupt won't touch the xStateListItem because the + scheduler is suspended. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + + /* Is the task waiting on an event also? If so remove it from + the event list too. Interrupts can touch the event list item, + even though the scheduler is suspended, so a critical section + is used. */ + taskENTER_CRITICAL(); + { + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + pxTCB->ucDelayAborted = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + /* Place the unblocked task into the appropriate ready list. */ + prvAddTaskToReadyList( pxTCB ); + + /* A task being unblocked cannot cause an immediate context + switch if preemption is turned off. */ + #if ( configUSE_PREEMPTION == 1 ) + { + /* Preemption is on, but a context switch should only be + performed if the unblocked task has a priority that is + equal to or higher than the currently executing task. */ + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* Pend the yield to be performed when the scheduler + is unsuspended. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + } + else + { + xReturn = pdFAIL; + } + } + ( void ) xTaskResumeAll(); + + return xReturn; + } + +#endif /* INCLUDE_xTaskAbortDelay */ +/*----------------------------------------------------------*/ + +BaseType_t xTaskIncrementTick( void ) +{ +TCB_t * pxTCB; +TickType_t xItemValue; +BaseType_t xSwitchRequired = pdFALSE; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + traceTASK_INCREMENT_TICK( xTickCount ); + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + /* Minor optimisation. The tick count cannot change in this + block. */ + const TickType_t xConstTickCount = xTickCount + ( TickType_t ) 1; + + /* Increment the RTOS tick, switching the delayed and overflowed + delayed lists if it wraps to 0. */ + xTickCount = xConstTickCount; + + if( xConstTickCount == ( TickType_t ) 0U ) /*lint !e774 'if' does not always evaluate to false as it is looking for an overflow. */ + { + taskSWITCH_DELAYED_LISTS(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* See if this tick has made a timeout expire. Tasks are stored in + the queue in the order of their wake time - meaning once one task + has been found whose block time has not expired there is no need to + look any further down the list. */ + if( xConstTickCount >= xNextTaskUnblockTime ) + { + for( ;; ) + { + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The delayed list is empty. Set xNextTaskUnblockTime + to the maximum possible value so it is extremely + unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass + next time through. */ + xNextTaskUnblockTime = portMAX_DELAY; /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + break; + } + else + { + /* The delayed list is not empty, get the value of the + item at the head of the delayed list. This is the time + at which the task at the head of the delayed list must + be removed from the Blocked state. */ + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xStateListItem ) ); + + if( xConstTickCount < xItemValue ) + { + /* It is not time to unblock this item yet, but the + item value is the time at which the task at the head + of the blocked list must be removed from the Blocked + state - so record the item value in + xNextTaskUnblockTime. */ + xNextTaskUnblockTime = xItemValue; + break; /*lint !e9011 Code structure here is deedmed easier to understand with multiple breaks. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* It is time to remove the item from the Blocked state. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + + /* Is the task waiting on an event also? If so remove + it from the event list. */ + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + ( void ) uxListRemove( &( pxTCB->xEventListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Place the unblocked task into the appropriate ready + list. */ + prvAddTaskToReadyList( pxTCB ); + + /* A task being unblocked cannot cause an immediate + context switch if preemption is turned off. */ + #if ( configUSE_PREEMPTION == 1 ) + { + /* Preemption is on, but a context switch should + only be performed if the unblocked task has a + priority that is equal to or higher than the + currently executing task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + } + } + } + + /* Tasks of equal priority to the currently running task will share + processing time (time slice) if preemption is on, and the application + writer has not explicitly turned time slicing off. */ + #if ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) ) + { + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ pxCurrentTCB->uxPriority ] ) ) > ( UBaseType_t ) 1 ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) ) */ + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the pended tick + count is being unwound (when the scheduler is being unlocked). */ + if( uxPendedTicks == ( UBaseType_t ) 0U ) + { + vApplicationTickHook(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TICK_HOOK */ + } + else + { + ++uxPendedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_PREEMPTION == 1 ) + { + if( xYieldPending != pdFALSE ) + { + xSwitchRequired = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_PREEMPTION */ + + return xSwitchRequired; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) + { + TCB_t *xTCB; + + /* If xTask is NULL then it is the task hook of the calling task that is + getting set. */ + if( xTask == NULL ) + { + xTCB = ( TCB_t * ) pxCurrentTCB; + } + else + { + xTCB = xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + { + xTCB->pxTaskTag = pxHookFunction; + } + taskEXIT_CRITICAL(); + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + TaskHookFunction_t xReturn; + + /* If xTask is NULL then set the calling task's hook. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + { + xReturn = pxTCB->pxTaskTag; + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + TaskHookFunction_t xTaskGetApplicationTaskTagFromISR( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + TaskHookFunction_t xReturn; + UBaseType_t uxSavedInterruptStatus; + + /* If xTask is NULL then set the calling task's hook. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + xReturn = pxTCB->pxTaskTag; + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) + { + TCB_t *xTCB; + BaseType_t xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = pxCurrentTCB; + } + else + { + xTCB = xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif /* configUSE_APPLICATION_TASK_TAG */ +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( UBaseType_t ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xYieldPending = pdTRUE; + } + else + { + xYieldPending = pdFALSE; + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the + accumulated time so far. The time the task started running was + stored in ulTaskSwitchedInTime. Note that there is no overflow + protection here so count values are only valid until the timer + overflows. The guard against negative values is to protect + against suspect run time stat counter implementations - which + are provided by the application, not the kernel. */ + if( ulTotalRunTime > ulTaskSwitchedInTime ) + { + pxCurrentTCB->ulRunTimeCounter += ( ulTotalRunTime - ulTaskSwitchedInTime ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + ulTaskSwitchedInTime = ulTotalRunTime; + } + #endif /* configGENERATE_RUN_TIME_STATS */ + + /* Check for stack overflow, if configured. */ + taskCHECK_FOR_STACK_OVERFLOW(); + + /* Before the currently running task is switched out, save its errno. */ + #if( configUSE_POSIX_ERRNO == 1 ) + { + pxCurrentTCB->iTaskErrno = FreeRTOS_errno; + } + #endif + + /* Select a new task to run using either the generic C or port + optimised asm code. */ + taskSELECT_HIGHEST_PRIORITY_TASK(); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + traceTASK_SWITCHED_IN(); + + /* After the new task is switched in, update the global errno. */ + #if( configUSE_POSIX_ERRNO == 1 ) + { + FreeRTOS_errno = pxCurrentTCB->iTaskErrno; + } + #endif + + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + /* Switch Newlib's _impure_ptr variable to point to the _reent + structure specific to this task. */ + _impure_ptr = &( pxCurrentTCB->xNewLib_reent ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait ) +{ + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH EITHER INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED AND THE QUEUE BEING ACCESSED LOCKED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. The queue that contains the event + list is locked, preventing simultaneous access from interrupts. */ + vListInsert( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait ) +{ + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. It is used by + the event groups implementation. */ + configASSERT( uxSchedulerSuspended != 0 ); + + /* Store the item value in the event list item. It is safe to access the + event list item here as interrupts won't access the event list item of a + task that is not in the Blocked state. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE ); + + /* Place the event list item of the TCB at the end of the appropriate event + list. It is safe to access the event list here because it is part of an + event group implementation - and interrupts don't access event groups + directly (instead they access them indirectly by pending function calls to + the task level). */ + vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TIMERS == 1 ) + + void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) + { + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called with the scheduler suspended. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) ); + + /* If the task should block indefinitely then set the block time to a + value that will be recognised as an indefinite delay inside the + prvAddCurrentTaskToDelayedList() function. */ + if( xWaitIndefinitely != pdFALSE ) + { + xTicksToWait = portMAX_DELAY; + } + + traceTASK_DELAY_UNTIL( ( xTickCount + xTicksToWait ) ); + prvAddCurrentTaskToDelayedList( xTicksToWait, xWaitIndefinitely ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList ) +{ +TCB_t *pxUnblockedTCB; +BaseType_t xReturn; + + /* THIS FUNCTION MUST BE CALLED FROM A CRITICAL SECTION. It can also be + called from a critical section within an ISR. */ + + /* The event list is sorted in priority order, so the first in the list can + be removed as it is known to be the highest priority. Remove the TCB from + the delayed list, and add it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means exclusive access to the event list is guaranteed here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + configASSERT( pxUnblockedTCB ); + ( void ) uxListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxUnblockedTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxUnblockedTCB ); + + #if( configUSE_TICKLESS_IDLE != 0 ) + { + /* If a task is blocked on a kernel object then xNextTaskUnblockTime + might be set to the blocked task's time out time. If the task is + unblocked for a reason other than a timeout xNextTaskUnblockTime is + normally left unchanged, because it is automatically reset to a new + value when the tick count equals xNextTaskUnblockTime. However if + tickless idling is used it might be more important to enter sleep mode + at the earliest possible time - so reset xNextTaskUnblockTime here to + ensure it is updated at the earliest possible time. */ + prvResetNextTaskUnblockTime(); + } + #endif + } + else + { + /* The delayed and ready lists cannot be accessed, so hold this task + pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has a higher + priority than the calling task. This allows the calling task to know if + it should force a context switch now. */ + xReturn = pdTRUE; + + /* Mark that a yield is pending in case the user is not using the + "xHigherPriorityTaskWoken" parameter to an ISR safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue ) +{ +TCB_t *pxUnblockedTCB; + + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. It is used by + the event flags implementation. */ + configASSERT( uxSchedulerSuspended != pdFALSE ); + + /* Store the new item value in the event list. */ + listSET_LIST_ITEM_VALUE( pxEventListItem, xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE ); + + /* Remove the event list form the event flag. Interrupts do not access + event flags. */ + pxUnblockedTCB = listGET_LIST_ITEM_OWNER( pxEventListItem ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + configASSERT( pxUnblockedTCB ); + ( void ) uxListRemove( pxEventListItem ); + + /* Remove the task from the delayed list and add it to the ready list. The + scheduler is suspended so interrupts will not be accessing the ready + lists. */ + ( void ) uxListRemove( &( pxUnblockedTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxUnblockedTCB ); + + if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The unblocked task has a priority above that of the calling task, so + a context switch is required. This function is called with the + scheduler suspended so xYieldPending is set so the context switch + occurs immediately that the scheduler is resumed (unsuspended). */ + xYieldPending = pdTRUE; + } +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + taskENTER_CRITICAL(); + { + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +void vTaskInternalSetTimeOutState( TimeOut_t * const pxTimeOut ) +{ + /* For internal use only as it does not use a critical section. */ + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) +{ +BaseType_t xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + /* Minor optimisation. The tick count cannot change in this block. */ + const TickType_t xConstTickCount = xTickCount; + const TickType_t xElapsedTime = xConstTickCount - pxTimeOut->xTimeOnEntering; + + #if( INCLUDE_xTaskAbortDelay == 1 ) + if( pxCurrentTCB->ucDelayAborted != ( uint8_t ) pdFALSE ) + { + /* The delay was aborted, which is not the same as a time out, + but has the same result. */ + pxCurrentTCB->ucDelayAborted = pdFALSE; + xReturn = pdTRUE; + } + else + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + if( *pxTicksToWait == portMAX_DELAY ) + { + /* If INCLUDE_vTaskSuspend is set to 1 and the block time + specified is the maximum block time then the task should block + indefinitely, and therefore never time out. */ + xReturn = pdFALSE; + } + else + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( xConstTickCount >= pxTimeOut->xTimeOnEntering ) ) /*lint !e525 Indentation preferred as is to make code within pre-processor directives clearer. */ + { + /* The tick count is greater than the time at which + vTaskSetTimeout() was called, but has also overflowed since + vTaskSetTimeOut() was called. It must have wrapped all the way + around and gone past again. This passed since vTaskSetTimeout() + was called. */ + xReturn = pdTRUE; + } + else if( xElapsedTime < *pxTicksToWait ) /*lint !e961 Explicit casting is only redundant with some compilers, whereas others require it to prevent integer conversion errors. */ + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= xElapsedTime; + vTaskInternalSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + *pxTicksToWait = 0; + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xYieldPending = pdTRUE; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask ) + { + UBaseType_t uxReturn; + TCB_t const *pxTCB; + + if( xTask != NULL ) + { + pxTCB = xTask; + uxReturn = pxTCB->uxTaskNumber; + } + else + { + uxReturn = 0U; + } + + return uxReturn; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle ) + { + TCB_t * pxTCB; + + if( xTask != NULL ) + { + pxTCB = xTask; + pxTCB->uxTaskNumber = uxHandle; + } + } + +#endif /* configUSE_TRACE_FACILITY */ + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + /** THIS IS THE RTOS IDLE TASK - WHICH IS CREATED AUTOMATICALLY WHEN THE + SCHEDULER IS STARTED. **/ + + /* In case a task that has a secure context deletes itself, in which case + the idle task is responsible for deleting the task's secure context, if + any. */ + portALLOCATE_SECURE_CONTEXT( configMINIMAL_SECURE_STACK_SIZE ); + + for( ;; ) + { + /* See if any tasks have deleted themselves - if so then the idle task + is responsible for freeing the deleted task's TCB and stack. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif /* configUSE_PREEMPTION */ + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( UBaseType_t ) 1 ) + { + taskYIELD(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) */ + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif /* configUSE_IDLE_HOOK */ + + /* This conditional compilation should use inequality to 0, not equality + to 1. This is to ensure portSUPPRESS_TICKS_AND_SLEEP() is called when + user defined low power mode implementations require + configUSE_TICKLESS_IDLE to be set to a value other than 1. */ + #if ( configUSE_TICKLESS_IDLE != 0 ) + { + TickType_t xExpectedIdleTime; + + /* It is not desirable to suspend then resume the scheduler on + each iteration of the idle task. Therefore, a preliminary + test of the expected idle time is performed without the + scheduler suspended. The result here is not necessarily + valid. */ + xExpectedIdleTime = prvGetExpectedIdleTime(); + + if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP ) + { + vTaskSuspendAll(); + { + /* Now the scheduler is suspended, the expected idle + time can be sampled again, and this time its value can + be used. */ + configASSERT( xNextTaskUnblockTime >= xTickCount ); + xExpectedIdleTime = prvGetExpectedIdleTime(); + + /* Define the following macro to set xExpectedIdleTime to 0 + if the application does not want + portSUPPRESS_TICKS_AND_SLEEP() to be called. */ + configPRE_SUPPRESS_TICKS_AND_SLEEP_PROCESSING( xExpectedIdleTime ); + + if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP ) + { + traceLOW_POWER_IDLE_BEGIN(); + portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ); + traceLOW_POWER_IDLE_END(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + ( void ) xTaskResumeAll(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configUSE_TICKLESS_IDLE */ + } +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TICKLESS_IDLE != 0 ) + + eSleepModeStatus eTaskConfirmSleepModeStatus( void ) + { + /* The idle task exists in addition to the application tasks. */ + const UBaseType_t uxNonApplicationTasks = 1; + eSleepModeStatus eReturn = eStandardSleep; + + if( listCURRENT_LIST_LENGTH( &xPendingReadyList ) != 0 ) + { + /* A task was made ready while the scheduler was suspended. */ + eReturn = eAbortSleep; + } + else if( xYieldPending != pdFALSE ) + { + /* A yield was pended while the scheduler was suspended. */ + eReturn = eAbortSleep; + } + else + { + /* If all the tasks are in the suspended list (which might mean they + have an infinite block time rather than actually being suspended) + then it is safe to turn all clocks off and just wait for external + interrupts. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == ( uxCurrentNumberOfTasks - uxNonApplicationTasks ) ) + { + eReturn = eNoTasksWaitingTimeout; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + return eReturn; + } + +#endif /* configUSE_TICKLESS_IDLE */ +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + + void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) + { + TCB_t *pxTCB; + + if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS ) + { + pxTCB = prvGetTCBFromHandle( xTaskToSet ); + pxTCB->pvThreadLocalStoragePointers[ xIndex ] = pvValue; + } + } + +#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */ +/*-----------------------------------------------------------*/ + +#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 ) + + void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) + { + void *pvReturn = NULL; + TCB_t *pxTCB; + + if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS ) + { + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + pvReturn = pxTCB->pvThreadLocalStoragePointers[ xIndex ]; + } + else + { + pvReturn = NULL; + } + + return pvReturn; + } + +#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */ +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( TaskHandle_t xTaskToModify, const MemoryRegion_t * const xRegions ) + { + TCB_t *pxTCB; + + /* If null is passed in here then we are modifying the MPU settings of + the calling task. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + +#endif /* portUSING_MPU_WRAPPERS */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseTaskLists( void ) +{ +UBaseType_t uxPriority; + + for( uxPriority = ( UBaseType_t ) 0U; uxPriority < ( UBaseType_t ) configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( &xDelayedTaskList1 ); + vListInitialise( &xDelayedTaskList2 ); + vListInitialise( &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( &xTasksWaitingTermination ); + } + #endif /* INCLUDE_vTaskDelete */ + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( &xSuspendedTaskList ); + } + #endif /* INCLUDE_vTaskSuspend */ + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + + /** THIS FUNCTION IS CALLED FROM THE RTOS IDLE TASK **/ + + #if ( INCLUDE_vTaskDelete == 1 ) + { + TCB_t *pxTCB; + + /* uxDeletedTasksWaitingCleanUp is used to prevent taskENTER_CRITICAL() + being called too often in the idle task. */ + while( uxDeletedTasksWaitingCleanUp > ( UBaseType_t ) 0U ) + { + taskENTER_CRITICAL(); + { + pxTCB = listGET_OWNER_OF_HEAD_ENTRY( ( &xTasksWaitingTermination ) ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + --uxCurrentNumberOfTasks; + --uxDeletedTasksWaitingCleanUp; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + #endif /* INCLUDE_vTaskDelete */ +} +/*-----------------------------------------------------------*/ + +#if( configUSE_TRACE_FACILITY == 1 ) + + void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) + { + TCB_t *pxTCB; + + /* xTask is NULL then get the state of the calling task. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + pxTaskStatus->xHandle = ( TaskHandle_t ) pxTCB; + pxTaskStatus->pcTaskName = ( const char * ) &( pxTCB->pcTaskName [ 0 ] ); + pxTaskStatus->uxCurrentPriority = pxTCB->uxPriority; + pxTaskStatus->pxStackBase = pxTCB->pxStack; + pxTaskStatus->xTaskNumber = pxTCB->uxTCBNumber; + + #if ( configUSE_MUTEXES == 1 ) + { + pxTaskStatus->uxBasePriority = pxTCB->uxBasePriority; + } + #else + { + pxTaskStatus->uxBasePriority = 0; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTaskStatus->ulRunTimeCounter = pxTCB->ulRunTimeCounter; + } + #else + { + pxTaskStatus->ulRunTimeCounter = 0; + } + #endif + + /* Obtaining the task state is a little fiddly, so is only done if the + value of eState passed into this function is eInvalid - otherwise the + state is just set to whatever is passed in. */ + if( eState != eInvalid ) + { + if( pxTCB == pxCurrentTCB ) + { + pxTaskStatus->eCurrentState = eRunning; + } + else + { + pxTaskStatus->eCurrentState = eState; + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + /* If the task is in the suspended list then there is a + chance it is actually just blocked indefinitely - so really + it should be reported as being in the Blocked state. */ + if( eState == eSuspended ) + { + vTaskSuspendAll(); + { + if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL ) + { + pxTaskStatus->eCurrentState = eBlocked; + } + } + ( void ) xTaskResumeAll(); + } + } + #endif /* INCLUDE_vTaskSuspend */ + } + } + else + { + pxTaskStatus->eCurrentState = eTaskGetState( pxTCB ); + } + + /* Obtaining the stack space takes some time, so the xGetFreeStackSpace + parameter is provided to allow it to be skipped. */ + if( xGetFreeStackSpace != pdFALSE ) + { + #if ( portSTACK_GROWTH > 0 ) + { + pxTaskStatus->usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxTCB->pxEndOfStack ); + } + #else + { + pxTaskStatus->usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxTCB->pxStack ); + } + #endif + } + else + { + pxTaskStatus->usStackHighWaterMark = 0; + } + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static UBaseType_t prvListTasksWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState ) + { + configLIST_VOLATILE TCB_t *pxNextTCB, *pxFirstTCB; + UBaseType_t uxTask = 0; + + if( listCURRENT_LIST_LENGTH( pxList ) > ( UBaseType_t ) 0 ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Populate an TaskStatus_t structure within the + pxTaskStatusArray array for each task that is referenced from + pxList. See the definition of TaskStatus_t in task.h for the + meaning of each TaskStatus_t structure member. */ + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + vTaskGetInfo( ( TaskHandle_t ) pxNextTCB, &( pxTaskStatusArray[ uxTask ] ), pdTRUE, eState ); + uxTask++; + } while( pxNextTCB != pxFirstTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return uxTask; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) + + static configSTACK_DEPTH_TYPE prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte ) + { + uint32_t ulCount = 0U; + + while( *pucStackByte == ( uint8_t ) tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + ulCount++; + } + + ulCount /= ( uint32_t ) sizeof( StackType_t ); /*lint !e961 Casting is not redundant on smaller architectures. */ + + return ( configSTACK_DEPTH_TYPE ) ulCount; + } + +#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark2 == 1 ) + + /* uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are the + same except for their return type. Using configSTACK_DEPTH_TYPE allows the + user to determine the return type. It gets around the problem of the value + overflowing on 8-bit types without breaking backward compatibility for + applications that expect an 8-bit return type. */ + configSTACK_DEPTH_TYPE uxTaskGetStackHighWaterMark2( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + uint8_t *pucEndOfStack; + configSTACK_DEPTH_TYPE uxReturn; + + /* uxTaskGetStackHighWaterMark() and uxTaskGetStackHighWaterMark2() are + the same except for their return type. Using configSTACK_DEPTH_TYPE + allows the user to determine the return type. It gets around the + problem of the value overflowing on 8-bit types without breaking + backward compatibility for applications that expect an 8-bit return + type. */ + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxStack; + } + #else + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = prvTaskCheckFreeStackSpace( pucEndOfStack ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskGetStackHighWaterMark2 */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + uint8_t *pucEndOfStack; + UBaseType_t uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxStack; + } + #else + { + pucEndOfStack = ( uint8_t * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( UBaseType_t ) prvTaskCheckFreeStackSpace( pucEndOfStack ); + + return uxReturn; + } + +#endif /* INCLUDE_uxTaskGetStackHighWaterMark */ +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( TCB_t *pxTCB ) + { + /* This call is required specifically for the TriCore port. It must be + above the vPortFree() calls. The call is also used by ports/demos that + want to allocate and clean RAM statically. */ + portCLEAN_UP_TCB( pxTCB ); + + /* Free up the memory allocated by the scheduler for the task. It is up + to the task to free any memory allocated at the application level. */ + #if ( configUSE_NEWLIB_REENTRANT == 1 ) + { + _reclaim_reent( &( pxTCB->xNewLib_reent ) ); + } + #endif /* configUSE_NEWLIB_REENTRANT */ + + #if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configSUPPORT_STATIC_ALLOCATION == 0 ) && ( portUSING_MPU_WRAPPERS == 0 ) ) + { + /* The task can only have been allocated dynamically - free both + the stack and TCB. */ + vPortFree( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + #elif( tskSTATIC_AND_DYNAMIC_ALLOCATION_POSSIBLE != 0 ) /*lint !e731 !e9029 Macro has been consolidated for readability reasons. */ + { + /* The task could have been allocated statically or dynamically, so + check what was statically allocated before trying to free the + memory. */ + if( pxTCB->ucStaticallyAllocated == tskDYNAMICALLY_ALLOCATED_STACK_AND_TCB ) + { + /* Both the stack and TCB were allocated dynamically, so both + must be freed. */ + vPortFree( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + else if( pxTCB->ucStaticallyAllocated == tskSTATICALLY_ALLOCATED_STACK_ONLY ) + { + /* Only the stack was statically allocated, so the TCB is the + only memory that must be freed. */ + vPortFree( pxTCB ); + } + else + { + /* Neither the stack nor the TCB were allocated dynamically, so + nothing needs to be freed. */ + configASSERT( pxTCB->ucStaticallyAllocated == tskSTATICALLY_ALLOCATED_STACK_AND_TCB ); + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + } + +#endif /* INCLUDE_vTaskDelete */ +/*-----------------------------------------------------------*/ + +static void prvResetNextTaskUnblockTime( void ) +{ +TCB_t *pxTCB; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set xNextTaskUnblockTime to + the maximum possible value so it is extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + ( pxTCB ) = listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); /*lint !e9079 void * is used as this macro is used with timers and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( ( pxTCB )->xStateListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE pxGetCurrentTaskNumber( void ) +{ +unsigned portBASE_TYPE uxNumber; + + portENTER_CRITICAL(); + uxNumber = pxCurrentTCB->uxTCBNumber; + portEXIT_CRITICAL(); + + return uxNumber; +} + +unsigned portBASE_TYPE pxGetCurrentTaskPriority( void ) +{ +unsigned portBASE_TYPE uxPriority; + + portENTER_CRITICAL(); + uxPriority = pxCurrentTCB->uxPriority; + portEXIT_CRITICAL(); + + return uxPriority; +} + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + TaskHandle_t xTaskGetCurrentTaskHandle( void ) + { + TaskHandle_t xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif /* ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + BaseType_t xTaskGetSchedulerState( void ) + { + BaseType_t xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif /* ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + BaseType_t xTaskPriorityInherit( TaskHandle_t const pxMutexHolder ) + { + TCB_t * const pxMutexHolderTCB = pxMutexHolder; + BaseType_t xReturn = pdFALSE; + + /* If the mutex was given back by an interrupt while the queue was + locked then the mutex holder might now be NULL. _RB_ Is this still + needed as interrupts can no longer use mutexes? */ + if( pxMutexHolder != NULL ) + { + /* If the holder of the mutex has a priority below the priority of + the task attempting to obtain the mutex then it will temporarily + inherit the priority of the task attempting to obtain the mutex. */ + if( pxMutexHolderTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new + priority. Only reset the event list item value if the value is + not being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxMutexHolderTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxMutexHolderTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the task being modified is in the ready state it will need + to be moved into a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxMutexHolderTCB->uxPriority ] ), &( pxMutexHolderTCB->xStateListItem ) ) != pdFALSE ) + { + if( uxListRemove( &( pxMutexHolderTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxMutexHolderTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Inherit the priority before being moved into the new list. */ + pxMutexHolderTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyList( pxMutexHolderTCB ); + } + else + { + /* Just inherit the priority. */ + pxMutexHolderTCB->uxPriority = pxCurrentTCB->uxPriority; + } + + traceTASK_PRIORITY_INHERIT( pxMutexHolderTCB, pxCurrentTCB->uxPriority ); + + /* Inheritance occurred. */ + xReturn = pdTRUE; + } + else + { + if( pxMutexHolderTCB->uxBasePriority < pxCurrentTCB->uxPriority ) + { + /* The base priority of the mutex holder is lower than the + priority of the task attempting to take the mutex, but the + current priority of the mutex holder is not lower than the + priority of the task attempting to take the mutex. + Therefore the mutex holder must have already inherited a + priority, but inheritance would have occurred if that had + not been the case. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder ) + { + TCB_t * const pxTCB = pxMutexHolder; + BaseType_t xReturn = pdFALSE; + + if( pxMutexHolder != NULL ) + { + /* A task can only have an inherited priority if it holds the mutex. + If the mutex is held by a task then it cannot be given from an + interrupt, and if a mutex is given by the holding task then it must + be the running state task. */ + configASSERT( pxTCB == pxCurrentTCB ); + configASSERT( pxTCB->uxMutexesHeld ); + ( pxTCB->uxMutexesHeld )--; + + /* Has the holder of the mutex inherited the priority of another + task? */ + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* Only disinherit if no other mutexes are held. */ + if( pxTCB->uxMutexesHeld == ( UBaseType_t ) 0 ) + { + /* A task can only have an inherited priority if it holds + the mutex. If the mutex is held by a task then it cannot be + given from an interrupt, and if a mutex is given by the + holding task then it must be the running state task. Remove + the holding task from the ready list. */ + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Disinherit the priority before adding the task into the + new ready list. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + pxTCB->uxPriority = pxTCB->uxBasePriority; + + /* Reset the event list item value. It cannot be in use for + any other purpose if this task is running, and it must be + running to give back the mutex. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + prvAddTaskToReadyList( pxTCB ); + + /* Return true to indicate that a context switch is required. + This is only actually required in the corner case whereby + multiple mutexes were held and the mutexes were given back + in an order different to that in which they were taken. + If a context switch did not occur when the first mutex was + returned, even if a task was waiting on it, then a context + switch should occur when the last mutex is returned whether + a task is waiting on it or not. */ + xReturn = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinheritAfterTimeout( TaskHandle_t const pxMutexHolder, UBaseType_t uxHighestPriorityWaitingTask ) + { + TCB_t * const pxTCB = pxMutexHolder; + UBaseType_t uxPriorityUsedOnEntry, uxPriorityToUse; + const UBaseType_t uxOnlyOneMutexHeld = ( UBaseType_t ) 1; + + if( pxMutexHolder != NULL ) + { + /* If pxMutexHolder is not NULL then the holder must hold at least + one mutex. */ + configASSERT( pxTCB->uxMutexesHeld ); + + /* Determine the priority to which the priority of the task that + holds the mutex should be set. This will be the greater of the + holding task's base priority and the priority of the highest + priority task that is waiting to obtain the mutex. */ + if( pxTCB->uxBasePriority < uxHighestPriorityWaitingTask ) + { + uxPriorityToUse = uxHighestPriorityWaitingTask; + } + else + { + uxPriorityToUse = pxTCB->uxBasePriority; + } + + /* Does the priority need to change? */ + if( pxTCB->uxPriority != uxPriorityToUse ) + { + /* Only disinherit if no other mutexes are held. This is a + simplification in the priority inheritance implementation. If + the task that holds the mutex is also holding other mutexes then + the other mutexes may have caused the priority inheritance. */ + if( pxTCB->uxMutexesHeld == uxOnlyOneMutexHeld ) + { + /* If a task has timed out because it already holds the + mutex it was trying to obtain then it cannot of inherited + its own priority. */ + configASSERT( pxTCB != pxCurrentTCB ); + + /* Disinherit the priority, remembering the previous + priority to facilitate determining the subject task's + state. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + uxPriorityUsedOnEntry = pxTCB->uxPriority; + pxTCB->uxPriority = uxPriorityToUse; + + /* Only reset the event list item value if the value is not + being used for anything else. */ + if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL ) + { + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxPriorityToUse ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* If the running task is not the task that holds the mutex + then the task that holds the mutex could be in either the + Ready, Blocked or Suspended states. Only remove the task + from its current state list if it is in the Ready state as + the task's priority is going to change and there is one + Ready list per priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxPriorityUsedOnEntry ] ), &( pxTCB->xStateListItem ) ) != pdFALSE ) + { + if( uxListRemove( &( pxTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + taskRESET_READY_PRIORITY( pxTCB->uxPriority ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + prvAddTaskToReadyList( pxTCB ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + + /* This is not the interrupt safe version of the enter critical + function so assert() if it is being called from an interrupt + context. Only API functions that end in "FromISR" can be used in an + interrupt. Only assert if the critical nesting count is 1 to + protect against recursive calls if the assert function also uses a + critical section. */ + if( pxCurrentTCB->uxCriticalNesting == 1 ) + { + portASSERT_IF_IN_ISR(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* portCRITICAL_NESTING_IN_TCB */ +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskExitCritical( void ) + { + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0U ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0U ) + { + portENABLE_INTERRUPTS(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* portCRITICAL_NESTING_IN_TCB */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) + + static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName ) + { + size_t x; + + /* Start by copying the entire string. */ + strcpy( pcBuffer, pcTaskName ); + + /* Pad the end of the string with spaces to ensure columns line up when + printed out. */ + for( x = strlen( pcBuffer ); x < ( size_t ) ( configMAX_TASK_NAME_LEN - 1 ); x++ ) + { + pcBuffer[ x ] = ' '; + } + + /* Terminate. */ + pcBuffer[ x ] = ( char ) 0x00; + + /* Return the new end of string. */ + return &( pcBuffer[ x ] ); + } + +#endif /* ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + void vTaskList( char * pcWriteBuffer ) + { + TaskStatus_t *pxTaskStatusArray; + UBaseType_t uxArraySize, x; + char cStatus; + + /* + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many + * of the demo applications. Do not consider it to be part of the + * scheduler. + * + * vTaskList() calls uxTaskGetSystemState(), then formats part of the + * uxTaskGetSystemState() output into a human readable table that + * displays task names, states and stack usage. + * + * vTaskList() has a dependency on the sprintf() C library function that + * might bloat the code size, use a lot of stack, and provide different + * results on different platforms. An alternative, tiny, third party, + * and limited functionality implementation of sprintf() is provided in + * many of the FreeRTOS/Demo sub-directories in a file called + * printf-stdarg.c (note printf-stdarg.c does not provide a full + * snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly + * through a call to vTaskList(). + */ + + + /* Make sure the write buffer does not contain a string. */ + *pcWriteBuffer = ( char ) 0x00; + + /* Take a snapshot of the number of tasks in case it changes while this + function is executing. */ + uxArraySize = uxCurrentNumberOfTasks; + + /* Allocate an array index for each task. NOTE! if + configSUPPORT_DYNAMIC_ALLOCATION is set to 0 then pvPortMalloc() will + equate to NULL. */ + pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation allocates a struct that has the alignment requirements of a pointer. */ + + if( pxTaskStatusArray != NULL ) + { + /* Generate the (binary) data. */ + uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, NULL ); + + /* Create a human readable table from the binary data. */ + for( x = 0; x < uxArraySize; x++ ) + { + switch( pxTaskStatusArray[ x ].eCurrentState ) + { + case eRunning: cStatus = tskRUNNING_CHAR; + break; + + case eReady: cStatus = tskREADY_CHAR; + break; + + case eBlocked: cStatus = tskBLOCKED_CHAR; + break; + + case eSuspended: cStatus = tskSUSPENDED_CHAR; + break; + + case eDeleted: cStatus = tskDELETED_CHAR; + break; + + case eInvalid: /* Fall through. */ + default: /* Should not get here, but it is included + to prevent static checking errors. */ + cStatus = ( char ) 0x00; + break; + } + + /* Write the task name to the string, padding with spaces so it + can be printed in tabular form more easily. */ + pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName ); + + /* Write the rest of the string. */ + sprintf( pcWriteBuffer, "\t%c\t%u\t%u\t%u\r\n", cStatus, ( unsigned int ) pxTaskStatusArray[ x ].uxCurrentPriority, ( unsigned int ) pxTaskStatusArray[ x ].usStackHighWaterMark, ( unsigned int ) pxTaskStatusArray[ x ].xTaskNumber ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + pcWriteBuffer += strlen( pcWriteBuffer ); /*lint !e9016 Pointer arithmetic ok on char pointers especially as in this case where it best denotes the intent of the code. */ + } + + /* Free the array again. NOTE! If configSUPPORT_DYNAMIC_ALLOCATION + is 0 then vPortFree() will be #defined to nothing. */ + vPortFree( pxTaskStatusArray ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) */ +/*----------------------------------------------------------*/ + +#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) ) + + void vTaskGetRunTimeStats( char *pcWriteBuffer ) + { + TaskStatus_t *pxTaskStatusArray; + UBaseType_t uxArraySize, x; + uint32_t ulTotalTime, ulStatsAsPercentage; + + #if( configUSE_TRACE_FACILITY != 1 ) + { + #error configUSE_TRACE_FACILITY must also be set to 1 in FreeRTOSConfig.h to use vTaskGetRunTimeStats(). + } + #endif + + /* + * PLEASE NOTE: + * + * This function is provided for convenience only, and is used by many + * of the demo applications. Do not consider it to be part of the + * scheduler. + * + * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part + * of the uxTaskGetSystemState() output into a human readable table that + * displays the amount of time each task has spent in the Running state + * in both absolute and percentage terms. + * + * vTaskGetRunTimeStats() has a dependency on the sprintf() C library + * function that might bloat the code size, use a lot of stack, and + * provide different results on different platforms. An alternative, + * tiny, third party, and limited functionality implementation of + * sprintf() is provided in many of the FreeRTOS/Demo sub-directories in + * a file called printf-stdarg.c (note printf-stdarg.c does not provide + * a full snprintf() implementation!). + * + * It is recommended that production systems call uxTaskGetSystemState() + * directly to get access to raw stats data, rather than indirectly + * through a call to vTaskGetRunTimeStats(). + */ + + /* Make sure the write buffer does not contain a string. */ + *pcWriteBuffer = ( char ) 0x00; + + /* Take a snapshot of the number of tasks in case it changes while this + function is executing. */ + uxArraySize = uxCurrentNumberOfTasks; + + /* Allocate an array index for each task. NOTE! If + configSUPPORT_DYNAMIC_ALLOCATION is set to 0 then pvPortMalloc() will + equate to NULL. */ + pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) ); /*lint !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack and this allocation allocates a struct that has the alignment requirements of a pointer. */ + + if( pxTaskStatusArray != NULL ) + { + /* Generate the (binary) data. */ + uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalTime ); + + /* For percentage calculations. */ + ulTotalTime /= 100UL; + + /* Avoid divide by zero errors. */ + if( ulTotalTime > 0UL ) + { + /* Create a human readable table from the binary data. */ + for( x = 0; x < uxArraySize; x++ ) + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTimeDiv100 has already been divided by 100. */ + ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalTime; + + /* Write the task name to the string, padding with + spaces so it can be printed in tabular form more + easily. */ + pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName ); + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcWriteBuffer, "\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcWriteBuffer, "\t%u\t\t%u%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcWriteBuffer, "\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcWriteBuffer, "\t%u\t\t<1%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter ); /*lint !e586 sprintf() allowed as this is compiled with many compilers and this is a utility function only - not part of the core kernel implementation. */ + } + #endif + } + + pcWriteBuffer += strlen( pcWriteBuffer ); /*lint !e9016 Pointer arithmetic ok on char pointers especially as in this case where it best denotes the intent of the code. */ + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + /* Free the array again. NOTE! If configSUPPORT_DYNAMIC_ALLOCATION + is 0 then vPortFree() will be #defined to nothing. */ + vPortFree( pxTaskStatusArray ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + +#endif /* ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) && ( configSUPPORT_STATIC_ALLOCATION == 1 ) ) */ +/*-----------------------------------------------------------*/ + +TickType_t uxTaskResetEventItemValue( void ) +{ +TickType_t uxReturn; + + uxReturn = listGET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ) ); + + /* Reset the event list item to its normal value - so it can be used with + queues and semaphores. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + TaskHandle_t pvTaskIncrementMutexHeldCount( void ) + { + /* If xSemaphoreCreateMutex() is called before any tasks have been created + then pxCurrentTCB will be NULL. */ + if( pxCurrentTCB != NULL ) + { + ( pxCurrentTCB->uxMutexesHeld )++; + } + + return pxCurrentTCB; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) + { + uint32_t ulReturn; + + taskENTER_CRITICAL(); + { + /* Only block if the notification count is not already non-zero. */ + if( pxCurrentTCB->ulNotifiedValue == 0UL ) + { + /* Mark this task as waiting for a notification. */ + pxCurrentTCB->ucNotifyState = taskWAITING_NOTIFICATION; + + if( xTicksToWait > ( TickType_t ) 0 ) + { + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); + traceTASK_NOTIFY_TAKE_BLOCK(); + + /* All ports are written to allow a yield in a critical + section (some will yield immediately, others wait until the + critical section exits) - but it is not something that + application code should ever do. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + traceTASK_NOTIFY_TAKE(); + ulReturn = pxCurrentTCB->ulNotifiedValue; + + if( ulReturn != 0UL ) + { + if( xClearCountOnExit != pdFALSE ) + { + pxCurrentTCB->ulNotifiedValue = 0UL; + } + else + { + pxCurrentTCB->ulNotifiedValue = ulReturn - ( uint32_t ) 1; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + pxCurrentTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + taskEXIT_CRITICAL(); + + return ulReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) + { + BaseType_t xReturn; + + taskENTER_CRITICAL(); + { + /* Only block if a notification is not already pending. */ + if( pxCurrentTCB->ucNotifyState != taskNOTIFICATION_RECEIVED ) + { + /* Clear bits in the task's notification value as bits may get + set by the notifying task or interrupt. This can be used to + clear the value to zero. */ + pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnEntry; + + /* Mark this task as waiting for a notification. */ + pxCurrentTCB->ucNotifyState = taskWAITING_NOTIFICATION; + + if( xTicksToWait > ( TickType_t ) 0 ) + { + prvAddCurrentTaskToDelayedList( xTicksToWait, pdTRUE ); + traceTASK_NOTIFY_WAIT_BLOCK(); + + /* All ports are written to allow a yield in a critical + section (some will yield immediately, others wait until the + critical section exits) - but it is not something that + application code should ever do. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + traceTASK_NOTIFY_WAIT(); + + if( pulNotificationValue != NULL ) + { + /* Output the current notification value, which may or may not + have changed. */ + *pulNotificationValue = pxCurrentTCB->ulNotifiedValue; + } + + /* If ucNotifyValue is set then either the task never entered the + blocked state (because a notification was already pending) or the + task unblocked because of a notification. Otherwise the task + unblocked because of a timeout. */ + if( pxCurrentTCB->ucNotifyState != taskNOTIFICATION_RECEIVED ) + { + /* A notification was not received. */ + xReturn = pdFALSE; + } + else + { + /* A notification was already pending or a notification was + received while the task was waiting. */ + pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnExit; + xReturn = pdTRUE; + } + + pxCurrentTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) + { + TCB_t * pxTCB; + BaseType_t xReturn = pdPASS; + uint8_t ucOriginalNotifyState; + + configASSERT( xTaskToNotify ); + pxTCB = xTaskToNotify; + + taskENTER_CRITICAL(); + { + if( pulPreviousNotificationValue != NULL ) + { + *pulPreviousNotificationValue = pxTCB->ulNotifiedValue; + } + + ucOriginalNotifyState = pxTCB->ucNotifyState; + + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + switch( eAction ) + { + case eSetBits : + pxTCB->ulNotifiedValue |= ulValue; + break; + + case eIncrement : + ( pxTCB->ulNotifiedValue )++; + break; + + case eSetValueWithOverwrite : + pxTCB->ulNotifiedValue = ulValue; + break; + + case eSetValueWithoutOverwrite : + if( ucOriginalNotifyState != taskNOTIFICATION_RECEIVED ) + { + pxTCB->ulNotifiedValue = ulValue; + } + else + { + /* The value could not be written to the task. */ + xReturn = pdFAIL; + } + break; + + case eNoAction: + /* The task is being notified without its notify value being + updated. */ + break; + + default: + /* Should not get here if all enums are handled. + Artificially force an assert by testing a value the + compiler can't assume is const. */ + configASSERT( pxTCB->ulNotifiedValue == ~0UL ); + + break; + } + + traceTASK_NOTIFY(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + #if( configUSE_TICKLESS_IDLE != 0 ) + { + /* If a task is blocked waiting for a notification then + xNextTaskUnblockTime might be set to the blocked task's time + out time. If the task is unblocked for a reason other than + a timeout xNextTaskUnblockTime is normally left unchanged, + because it will automatically get reset to a new value when + the tick count equals xNextTaskUnblockTime. However if + tickless idling is used it might be more important to enter + sleep mode at the earliest possible time - so reset + xNextTaskUnblockTime here to ensure it is updated at the + earliest possible time. */ + prvResetNextTaskUnblockTime(); + } + #endif + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + taskYIELD_IF_USING_PREEMPTION(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken ) + { + TCB_t * pxTCB; + uint8_t ucOriginalNotifyState; + BaseType_t xReturn = pdPASS; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToNotify ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + pxTCB = xTaskToNotify; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pulPreviousNotificationValue != NULL ) + { + *pulPreviousNotificationValue = pxTCB->ulNotifiedValue; + } + + ucOriginalNotifyState = pxTCB->ucNotifyState; + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + switch( eAction ) + { + case eSetBits : + pxTCB->ulNotifiedValue |= ulValue; + break; + + case eIncrement : + ( pxTCB->ulNotifiedValue )++; + break; + + case eSetValueWithOverwrite : + pxTCB->ulNotifiedValue = ulValue; + break; + + case eSetValueWithoutOverwrite : + if( ucOriginalNotifyState != taskNOTIFICATION_RECEIVED ) + { + pxTCB->ulNotifiedValue = ulValue; + } + else + { + /* The value could not be written to the task. */ + xReturn = pdFAIL; + } + break; + + case eNoAction : + /* The task is being notified without its notify value being + updated. */ + break; + + default: + /* Should not get here if all enums are handled. + Artificially force an assert by testing a value the + compiler can't assume is const. */ + configASSERT( pxTCB->ulNotifiedValue == ~0UL ); + break; + } + + traceTASK_NOTIFY_FROM_ISR(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed and ready lists cannot be accessed, so hold + this task pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + + /* Mark that a yield is pending in case the user is not + using the "xHigherPriorityTaskWoken" parameter to an ISR + safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken ) + { + TCB_t * pxTCB; + uint8_t ucOriginalNotifyState; + UBaseType_t uxSavedInterruptStatus; + + configASSERT( xTaskToNotify ); + + /* RTOS ports that support interrupt nesting have the concept of a + maximum system call (or maximum API call) interrupt priority. + Interrupts that are above the maximum system call priority are keep + permanently enabled, even when the RTOS kernel is in a critical section, + but cannot make any calls to FreeRTOS API functions. If configASSERT() + is defined in FreeRTOSConfig.h then + portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion + failure if a FreeRTOS API function is called from an interrupt that has + been assigned a priority above the configured maximum system call + priority. Only FreeRTOS functions that end in FromISR can be called + from interrupts that have been assigned a priority at or (logically) + below the maximum system call interrupt priority. FreeRTOS maintains a + separate interrupt safe API to ensure interrupt entry is as fast and as + simple as possible. More information (albeit Cortex-M specific) is + provided on the following link: + http://www.freertos.org/RTOS-Cortex-M3-M4.html */ + portASSERT_IF_INTERRUPT_PRIORITY_INVALID(); + + pxTCB = xTaskToNotify; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + ucOriginalNotifyState = pxTCB->ucNotifyState; + pxTCB->ucNotifyState = taskNOTIFICATION_RECEIVED; + + /* 'Giving' is equivalent to incrementing a count in a counting + semaphore. */ + ( pxTCB->ulNotifiedValue )++; + + traceTASK_NOTIFY_GIVE_FROM_ISR(); + + /* If the task is in the blocked state specifically to wait for a + notification then unblock it now. */ + if( ucOriginalNotifyState == taskWAITING_NOTIFICATION ) + { + /* The task should not have been on an event list. */ + configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL ); + + if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE ) + { + ( void ) uxListRemove( &( pxTCB->xStateListItem ) ); + prvAddTaskToReadyList( pxTCB ); + } + else + { + /* The delayed and ready lists cannot be accessed, so hold + this task pending until the scheduler is resumed. */ + vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + + if( pxTCB->uxPriority > pxCurrentTCB->uxPriority ) + { + /* The notified task has a priority above the currently + executing task so a yield is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + + /* Mark that a yield is pending in case the user is not + using the "xHigherPriorityTaskWoken" parameter in an ISR + safe FreeRTOS function. */ + xYieldPending = pdTRUE; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ + +/*-----------------------------------------------------------*/ + +#if( configUSE_TASK_NOTIFICATIONS == 1 ) + + BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask ) + { + TCB_t *pxTCB; + BaseType_t xReturn; + + /* If null is passed in here then it is the calling task that is having + its notification state cleared. */ + pxTCB = prvGetTCBFromHandle( xTask ); + + taskENTER_CRITICAL(); + { + if( pxTCB->ucNotifyState == taskNOTIFICATION_RECEIVED ) + { + pxTCB->ucNotifyState = taskNOT_WAITING_NOTIFICATION; + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + } + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif /* configUSE_TASK_NOTIFICATIONS */ +/*-----------------------------------------------------------*/ + +#if( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) ) + TickType_t xTaskGetIdleRunTimeCounter( void ) + { + return xIdleTaskHandle->ulRunTimeCounter; + } +#endif +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( TickType_t xTicksToWait, const BaseType_t xCanBlockIndefinitely ) +{ +TickType_t xTimeToWake; +const TickType_t xConstTickCount = xTickCount; + + #if( INCLUDE_xTaskAbortDelay == 1 ) + { + /* About to enter a delayed list, so ensure the ucDelayAborted flag is + reset to pdFALSE so it can be detected as having been set to pdTRUE + when the task leaves the Blocked state. */ + pxCurrentTCB->ucDelayAborted = pdFALSE; + } + #endif + + /* Remove the task from the ready list before adding it to the blocked list + as the same list item is used for both lists. */ + if( uxListRemove( &( pxCurrentTCB->xStateListItem ) ) == ( UBaseType_t ) 0 ) + { + /* The current task must be in a ready list, so there is no need to + check, and the port reset macro can be called directly. */ + portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority ); /*lint !e931 pxCurrentTCB cannot change as it is the calling task. pxCurrentTCB->uxPriority and uxTopReadyPriority cannot change as called with scheduler suspended or in a critical section. */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( ( xTicksToWait == portMAX_DELAY ) && ( xCanBlockIndefinitely != pdFALSE ) ) + { + /* Add the task to the suspended task list instead of a delayed task + list to ensure it is not woken by a timing event. It will block + indefinitely. */ + vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event + does not occur. This may overflow but this doesn't matter, the + kernel will manage it correctly. */ + xTimeToWake = xConstTickCount + xTicksToWait; + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xStateListItem ), xTimeToWake ); + + if( xTimeToWake < xConstTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow + list. */ + vListInsert( pxOverflowDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* The wake time has not overflowed, so the current block list + is used. */ + vListInsert( pxDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + + /* If the task entering the blocked state was placed at the + head of the list of blocked tasks then xNextTaskUnblockTime + needs to be updated too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + } + #else /* INCLUDE_vTaskSuspend */ + { + /* Calculate the time at which the task should be woken if the event + does not occur. This may overflow but this doesn't matter, the kernel + will manage it correctly. */ + xTimeToWake = xConstTickCount + xTicksToWait; + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xStateListItem ), xTimeToWake ); + + if( xTimeToWake < xConstTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( pxOverflowDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + } + else + { + /* The wake time has not overflowed, so the current block list is used. */ + vListInsert( pxDelayedTaskList, &( pxCurrentTCB->xStateListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + /* Avoid compiler warning when INCLUDE_vTaskSuspend is not 1. */ + ( void ) xCanBlockIndefinitely; + } + #endif /* INCLUDE_vTaskSuspend */ +} + +/* Code below here allows additional code to be inserted into this source file, +especially where access to file scope functions and data is needed (for example +when performing module tests). */ + +#ifdef FREERTOS_MODULE_TEST + #include "tasks_test_access_functions.h" +#endif + + +#if( configINCLUDE_FREERTOS_TASK_C_ADDITIONS_H == 1 ) + + #include "freertos_tasks_c_additions.h" + + #ifdef FREERTOS_TASKS_C_ADDITIONS_INIT + static void freertos_tasks_c_additions_init( void ) + { + FREERTOS_TASKS_C_ADDITIONS_INIT(); + } + #endif + +#endif + + diff --git a/lib/FreeRTOS-SAMD51/src/timers.c b/lib/FreeRTOS-SAMD51/src/timers.c new file mode 100644 index 0000000..ad18f3e --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/timers.c @@ -0,0 +1,1102 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + +/* Standard includes. */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#if ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 0 ) + #error configUSE_TIMERS must be set to 1 to make the xTimerPendFunctionCall() function available. +#endif + +/* Lint e9021, e961 and e750 are suppressed as a MISRA exception justified +because the MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined +for the header files above, but not in this file, in order to generate the +correct privileged Vs unprivileged linkage and placement. */ +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e9021 !e961 !e750. */ + + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( TickType_t ) 0U + +/* The name assigned to the timer service task. This can be overridden by +defining trmTIMER_SERVICE_TASK_NAME in FreeRTOSConfig.h. */ +#ifndef configTIMER_SERVICE_TASK_NAME + #define configTIMER_SERVICE_TASK_NAME "Tmr Svc" +#endif + +/* Bit definitions used in the ucStatus member of a timer structure. */ +#define tmrSTATUS_IS_ACTIVE ( ( uint8_t ) 0x01 ) +#define tmrSTATUS_IS_STATICALLY_ALLOCATED ( ( uint8_t ) 0x02 ) +#define tmrSTATUS_IS_AUTORELOAD ( ( uint8_t ) 0x04 ) + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +{ + const char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + ListItem_t xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + TickType_t xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + TimerCallbackFunction_t pxCallbackFunction; /*<< The function that will be called when the timer expires. */ + #if( configUSE_TRACE_FACILITY == 1 ) + UBaseType_t uxTimerNumber; /*<< An ID assigned by trace tools such as FreeRTOS+Trace */ + #endif + uint8_t ucStatus; /*<< Holds bits to say if the timer was statically allocated or not, and if it is active or not. */ +} xTIMER; + +/* The old xTIMER name is maintained above then typedefed to the new Timer_t +name below to enable the use of older kernel aware debuggers. */ +typedef xTIMER Timer_t; + +/* The definition of messages that can be sent and received on the timer queue. +Two types of message can be queued - messages that manipulate a software timer, +and messages that request the execution of a non-timer related callback. The +two message types are defined in two separate structures, xTimerParametersType +and xCallbackParametersType respectively. */ +typedef struct tmrTimerParameters +{ + TickType_t xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + Timer_t * pxTimer; /*<< The timer to which the command will be applied. */ +} TimerParameter_t; + + +typedef struct tmrCallbackParameters +{ + PendedFunction_t pxCallbackFunction; /* << The callback function to execute. */ + void *pvParameter1; /* << The value that will be used as the callback functions first parameter. */ + uint32_t ulParameter2; /* << The value that will be used as the callback functions second parameter. */ +} CallbackParameters_t; + +/* The structure that contains the two message types, along with an identifier +that is used to determine which message type is valid. */ +typedef struct tmrTimerQueueMessage +{ + BaseType_t xMessageID; /*<< The command being sent to the timer service task. */ + union + { + TimerParameter_t xTimerParameters; + + /* Don't include xCallbackParameters if it is not going to be used as + it makes the structure (and therefore the timer queue) larger. */ + #if ( INCLUDE_xTimerPendFunctionCall == 1 ) + CallbackParameters_t xCallbackParameters; + #endif /* INCLUDE_xTimerPendFunctionCall */ + } u; +} DaemonTaskMessage_t; + +/*lint -save -e956 A manual analysis and inspection has been used to determine +which static variables must be declared volatile. */ + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access these lists. +xActiveTimerList1 and xActiveTimerList2 could be at function scope but that +breaks some kernel aware debuggers, and debuggers that reply on removing the +static qualifier. */ +PRIVILEGED_DATA static List_t xActiveTimerList1; +PRIVILEGED_DATA static List_t xActiveTimerList2; +PRIVILEGED_DATA static List_t *pxCurrentTimerList; +PRIVILEGED_DATA static List_t *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static QueueHandle_t xTimerQueue = NULL; +PRIVILEGED_DATA static TaskHandle_t xTimerTaskHandle = NULL; + +/*lint -restore */ + +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + /* If static allocation is supported then the application must provide the + following callback function - which enables the application to optionally + provide the memory that will be used by the timer task as the task's stack + and TCB. */ + extern void vApplicationGetTimerTaskMemory( StaticTask_t **ppxTimerTaskTCBBuffer, StackType_t **ppxTimerTaskStackBuffer, uint32_t *pulTimerTaskStackSize ); + +#endif + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static portTASK_FUNCTION_PROTO( prvTimerTask, pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( void ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * Called after a Timer_t structure has been allocated either statically or + * dynamically to fill in the structure's members. + */ +static void prvInitialiseNewTimer( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + Timer_t *pxNewTimer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +BaseType_t xTimerCreateTimerTask( void ) +{ +BaseType_t xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + StaticTask_t *pxTimerTaskTCBBuffer = NULL; + StackType_t *pxTimerTaskStackBuffer = NULL; + uint32_t ulTimerTaskStackSize; + + vApplicationGetTimerTaskMemory( &pxTimerTaskTCBBuffer, &pxTimerTaskStackBuffer, &ulTimerTaskStackSize ); + xTimerTaskHandle = xTaskCreateStatic( prvTimerTask, + configTIMER_SERVICE_TASK_NAME, + ulTimerTaskStackSize, + NULL, + ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, + pxTimerTaskStackBuffer, + pxTimerTaskTCBBuffer ); + + if( xTimerTaskHandle != NULL ) + { + xReturn = pdPASS; + } + } + #else + { + xReturn = xTaskCreate( prvTimerTask, + configTIMER_SERVICE_TASK_NAME, + configTIMER_TASK_STACK_DEPTH, + NULL, + ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, + &xTimerTaskHandle ); + } + #endif /* configSUPPORT_STATIC_ALLOCATION */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + + TimerHandle_t xTimerCreate( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction ) + { + Timer_t *pxNewTimer; + + pxNewTimer = ( Timer_t * ) pvPortMalloc( sizeof( Timer_t ) ); /*lint !e9087 !e9079 All values returned by pvPortMalloc() have at least the alignment required by the MCU's stack, and the first member of Timer_t is always a pointer to the timer's mame. */ + + if( pxNewTimer != NULL ) + { + /* Status is thus far zero as the timer is not created statically + and has not been started. The autoreload bit may get set in + prvInitialiseNewTimer. */ + pxNewTimer->ucStatus = 0x00; + prvInitialiseNewTimer( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction, pxNewTimer ); + } + + return pxNewTimer; + } + +#endif /* configSUPPORT_DYNAMIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + + TimerHandle_t xTimerCreateStatic( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + StaticTimer_t *pxTimerBuffer ) + { + Timer_t *pxNewTimer; + + #if( configASSERT_DEFINED == 1 ) + { + /* Sanity check that the size of the structure used to declare a + variable of type StaticTimer_t equals the size of the real timer + structure. */ + volatile size_t xSize = sizeof( StaticTimer_t ); + configASSERT( xSize == sizeof( Timer_t ) ); + ( void ) xSize; /* Keeps lint quiet when configASSERT() is not defined. */ + } + #endif /* configASSERT_DEFINED */ + + /* A pointer to a StaticTimer_t structure MUST be provided, use it. */ + configASSERT( pxTimerBuffer ); + pxNewTimer = ( Timer_t * ) pxTimerBuffer; /*lint !e740 !e9087 StaticTimer_t is a pointer to a Timer_t, so guaranteed to be aligned and sized correctly (checked by an assert()), so this is safe. */ + + if( pxNewTimer != NULL ) + { + /* Timers can be created statically or dynamically so note this + timer was created statically in case it is later deleted. The + autoreload bit may get set in prvInitialiseNewTimer(). */ + pxNewTimer->ucStatus = tmrSTATUS_IS_STATICALLY_ALLOCATED; + + prvInitialiseNewTimer( pcTimerName, xTimerPeriodInTicks, uxAutoReload, pvTimerID, pxCallbackFunction, pxNewTimer ); + } + + return pxNewTimer; + } + +#endif /* configSUPPORT_STATIC_ALLOCATION */ +/*-----------------------------------------------------------*/ + +static void prvInitialiseNewTimer( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + Timer_t *pxNewTimer ) +{ + /* 0 is not a valid value for xTimerPeriodInTicks. */ + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function + parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + if( uxAutoReload != pdFALSE ) + { + pxNewTimer->ucStatus |= tmrSTATUS_IS_AUTORELOAD; + } + traceTIMER_CREATE( pxNewTimer ); + } +} +/*-----------------------------------------------------------*/ + +BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) +{ +BaseType_t xReturn = pdFAIL; +DaemonTaskMessage_t xMessage; + + configASSERT( xTimer ); + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.u.xTimerParameters.xMessageValue = xOptionalValue; + xMessage.u.xTimerParameters.pxTimer = xTimer; + + if( xCommandID < tmrFIRST_FROM_ISR_COMMAND ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ) +{ + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; +} +/*-----------------------------------------------------------*/ + +TickType_t xTimerGetPeriod( TimerHandle_t xTimer ) +{ +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + return pxTimer->xTimerPeriodInTicks; +} +/*-----------------------------------------------------------*/ + +void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) +{ +Timer_t * pxTimer = xTimer; + + configASSERT( xTimer ); + taskENTER_CRITICAL(); + { + if( uxAutoReload != pdFALSE ) + { + pxTimer->ucStatus |= tmrSTATUS_IS_AUTORELOAD; + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_AUTORELOAD; + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ) +{ +Timer_t * pxTimer = xTimer; +TickType_t xReturn; + + configASSERT( xTimer ); + xReturn = listGET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ) ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +const char * pcTimerGetName( TimerHandle_t xTimer ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ +{ +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + return pxTimer->pcTimerName; +} +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow ) +{ +BaseType_t xResult; +Timer_t * const pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); /*lint !e9087 !e9079 void * is used as this macro is used with tasks and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + /* The timer is inserted into a list using a time relative to anything + other than the current time. It will therefore be inserted into the + correct list relative to the time this task thinks it is now. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) != pdFALSE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + mtCOVERAGE_TEST_MARKER(); + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static portTASK_FUNCTION( prvTimerTask, pvParameters ) +{ +TickType_t xNextExpireTime; +BaseType_t xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + #if( configUSE_DAEMON_TASK_STARTUP_HOOK == 1 ) + { + extern void vApplicationDaemonTaskStartupHook( void ); + + /* Allow the application writer to execute some code in the context of + this task at the point the task starts executing. This is useful if the + application includes initialisation code that would benefit from + executing after the scheduler has been started. */ + vApplicationDaemonTaskStartupHook(); + } + #endif /* configUSE_DAEMON_TASK_STARTUP_HOOK */ + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty ) +{ +TickType_t xTimeNow; +BaseType_t xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampleTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + ( void ) xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + if( xListWasEmpty != pdFALSE ) + { + /* The current timer list is empty - is the overflow list + also empty? */ + xListWasEmpty = listLIST_IS_EMPTY( pxOverflowTimerList ); + } + + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ), xListWasEmpty ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the + block time to expire. If a command arrived between the + critical section being exited and this yield then the yield + will not cause the task to block. */ + portYIELD_WITHIN_API(); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + } + else + { + ( void ) xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty ) +{ +TickType_t xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( TickType_t ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched ) +{ +TickType_t xTimeNow; +PRIVILEGED_DATA static TickType_t xLastTime = ( TickType_t ) 0U; /*lint !e956 Variable is only accessible to one task. */ + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists(); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime ) +{ +BaseType_t xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( TickType_t ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) /*lint !e961 MISRA exception as the casts are only redundant for some ports. */ + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +DaemonTaskMessage_t xMessage; +Timer_t *pxTimer; +BaseType_t xTimerListsWereSwitched, xResult; +TickType_t xTimeNow; + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) /*lint !e603 xMessage does not have to be initialised as it is passed out, not in, and it is not used unless xQueueReceive() returns pdTRUE. */ + { + #if ( INCLUDE_xTimerPendFunctionCall == 1 ) + { + /* Negative commands are pended function calls rather than timer + commands. */ + if( xMessage.xMessageID < ( BaseType_t ) 0 ) + { + const CallbackParameters_t * const pxCallback = &( xMessage.u.xCallbackParameters ); + + /* The timer uses the xCallbackParameters member to request a + callback be executed. Check the callback is not NULL. */ + configASSERT( pxCallback ); + + /* Call the function. */ + pxCallback->pxCallbackFunction( pxCallback->pvParameter1, pxCallback->ulParameter2 ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* INCLUDE_xTimerPendFunctionCall */ + + /* Commands that are positive are timer commands rather than pended + function calls. */ + if( xMessage.xMessageID >= ( BaseType_t ) 0 ) + { + /* The messages uses the xTimerParameters member to work on a + software timer. */ + pxTimer = xMessage.u.xTimerParameters.pxTimer; + + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) /*lint !e961. The cast is only redundant when NULL is passed into the macro. */ + { + /* The timer is in a list, remove it. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.u.xTimerParameters.xMessageValue ); + + /* In this case the xTimerListsWereSwitched parameter is not used, but + it must be present in the function call. prvSampleTimeNow() must be + called after the message is received from xTimerQueue so there is no + possibility of a higher priority task adding a message to the message + queue with a time that is ahead of the timer daemon task (because it + pre-empted the timer daemon task after the xTimeNow value was set). */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + case tmrCOMMAND_START_FROM_ISR : + case tmrCOMMAND_RESET : + case tmrCOMMAND_RESET_FROM_ISR : + case tmrCOMMAND_START_DONT_TRACE : + /* Start or restart a timer. */ + pxTimer->ucStatus |= tmrSTATUS_IS_ACTIVE; + if( prvInsertTimerInActiveList( pxTimer, xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.u.xTimerParameters.xMessageValue ) != pdFALSE ) + { + /* The timer expired before it was added to the active + timer list. Process it now. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); + traceTIMER_EXPIRED( pxTimer ); + + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + break; + + case tmrCOMMAND_STOP : + case tmrCOMMAND_STOP_FROM_ISR : + /* The timer has already been removed from the active list. */ + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + break; + + case tmrCOMMAND_CHANGE_PERIOD : + case tmrCOMMAND_CHANGE_PERIOD_FROM_ISR : + pxTimer->ucStatus |= tmrSTATUS_IS_ACTIVE; + pxTimer->xTimerPeriodInTicks = xMessage.u.xTimerParameters.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + + /* The new period does not really have a reference, and can + be longer or shorter than the old one. The command time is + therefore set to the current time, and as the period cannot + be zero the next expiry time can only be in the future, + meaning (unlike for the xTimerStart() case above) there is + no fail case that needs to be handled here. */ + ( void ) prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + #if ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + { + /* The timer has already been removed from the active list, + just free up the memory if the memory was dynamically + allocated. */ + if( ( pxTimer->ucStatus & tmrSTATUS_IS_STATICALLY_ALLOCATED ) == ( uint8_t ) 0 ) + { + vPortFree( pxTimer ); + } + else + { + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + } + } + #else + { + /* If dynamic allocation is not enabled, the memory + could not have been dynamically allocated. So there is + no need to free the memory - just mark the timer as + "not active". */ + pxTimer->ucStatus &= ~tmrSTATUS_IS_ACTIVE; + } + #endif /* configSUPPORT_DYNAMIC_ALLOCATION */ + break; + + default : + /* Don't expect to get here. */ + break; + } + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( void ) +{ +TickType_t xNextExpireTime, xReloadTime; +List_t *pxTemp; +Timer_t *pxTimer; +BaseType_t xResult; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); /*lint !e9087 !e9079 void * is used as this macro is used with tasks and co-routines too. Alignment is known to be fine as the type of the pointer stored and retrieved is the same. */ + ( void ) uxListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer ); + + if( ( pxTimer->ucStatus & tmrSTATUS_IS_AUTORELOAD ) != 0 ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + + #if( configSUPPORT_STATIC_ALLOCATION == 1 ) + { + /* The timer queue is allocated statically in case + configSUPPORT_DYNAMIC_ALLOCATION is 0. */ + static StaticQueue_t xStaticTimerQueue; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ + static uint8_t ucStaticTimerQueueStorage[ ( size_t ) configTIMER_QUEUE_LENGTH * sizeof( DaemonTaskMessage_t ) ]; /*lint !e956 Ok to declare in this manner to prevent additional conditional compilation guards in other locations. */ + + xTimerQueue = xQueueCreateStatic( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, ( UBaseType_t ) sizeof( DaemonTaskMessage_t ), &( ucStaticTimerQueueStorage[ 0 ] ), &xStaticTimerQueue ); + } + #else + { + xTimerQueue = xQueueCreate( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, sizeof( DaemonTaskMessage_t ) ); + } + #endif + + #if ( configQUEUE_REGISTRY_SIZE > 0 ) + { + if( xTimerQueue != NULL ) + { + vQueueAddToRegistry( xTimerQueue, "TmrQ" ); + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + #endif /* configQUEUE_REGISTRY_SIZE */ + } + else + { + mtCOVERAGE_TEST_MARKER(); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ) +{ +BaseType_t xReturn; +Timer_t *pxTimer = xTimer; + + configASSERT( xTimer ); + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + if( ( pxTimer->ucStatus & tmrSTATUS_IS_ACTIVE ) == 0 ) + { + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} /*lint !e818 Can't be pointer to const due to the typedef. */ +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( const TimerHandle_t xTimer ) +{ +Timer_t * const pxTimer = xTimer; +void *pvReturn; + + configASSERT( xTimer ); + + taskENTER_CRITICAL(); + { + pvReturn = pxTimer->pvTimerID; + } + taskEXIT_CRITICAL(); + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) +{ +Timer_t * const pxTimer = xTimer; + + configASSERT( xTimer ); + + taskENTER_CRITICAL(); + { + pxTimer->pvTimerID = pvNewID; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +#if( INCLUDE_xTimerPendFunctionCall == 1 ) + + BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken ) + { + DaemonTaskMessage_t xMessage; + BaseType_t xReturn; + + /* Complete the message with the function parameters and post it to the + daemon task. */ + xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR; + xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend; + xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1; + xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2; + + xReturn = xQueueSendFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + + tracePEND_FUNC_CALL_FROM_ISR( xFunctionToPend, pvParameter1, ulParameter2, xReturn ); + + return xReturn; + } + +#endif /* INCLUDE_xTimerPendFunctionCall */ +/*-----------------------------------------------------------*/ + +#if( INCLUDE_xTimerPendFunctionCall == 1 ) + + BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) + { + DaemonTaskMessage_t xMessage; + BaseType_t xReturn; + + /* This function can only be called after a timer has been created or + after the scheduler has been started because, until then, the timer + queue does not exist. */ + configASSERT( xTimerQueue ); + + /* Complete the message with the function parameters and post it to the + daemon task. */ + xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK; + xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend; + xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1; + xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2; + + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait ); + + tracePEND_FUNC_CALL( xFunctionToPend, pvParameter1, ulParameter2, xReturn ); + + return xReturn; + } + +#endif /* INCLUDE_xTimerPendFunctionCall */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + UBaseType_t uxTimerGetTimerNumber( TimerHandle_t xTimer ) + { + return ( ( Timer_t * ) xTimer )->uxTimerNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTimerSetTimerNumber( TimerHandle_t xTimer, UBaseType_t uxTimerNumber ) + { + ( ( Timer_t * ) xTimer )->uxTimerNumber = uxTimerNumber; + } + +#endif /* configUSE_TRACE_FACILITY */ +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ + + + diff --git a/lib/FreeRTOS-SAMD51/src/timers.h b/lib/FreeRTOS-SAMD51/src/timers.h new file mode 100644 index 0000000..cb72179 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/src/timers.h @@ -0,0 +1,1295 @@ +/* + * FreeRTOS Kernel V10.2.1 + * Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * Permission is hereby granted, free of charge, to any person obtaining a copy of + * this software and associated documentation files (the "Software"), to deal in + * the Software without restriction, including without limitation the rights to + * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of + * the Software, and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS + * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR + * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER + * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +/*lint -save -e537 This headers are only multiply included if the application code +happens to also be including task.h. */ +#include "task.h" +/*lint -restore */ + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. The commands that are sent from interrupts must use the +highest numbers as tmrFIRST_FROM_ISR_COMMAND is used to determine if the task +or interrupt version of the queue send function should be used. */ +#define tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR ( ( BaseType_t ) -2 ) +#define tmrCOMMAND_EXECUTE_CALLBACK ( ( BaseType_t ) -1 ) +#define tmrCOMMAND_START_DONT_TRACE ( ( BaseType_t ) 0 ) +#define tmrCOMMAND_START ( ( BaseType_t ) 1 ) +#define tmrCOMMAND_RESET ( ( BaseType_t ) 2 ) +#define tmrCOMMAND_STOP ( ( BaseType_t ) 3 ) +#define tmrCOMMAND_CHANGE_PERIOD ( ( BaseType_t ) 4 ) +#define tmrCOMMAND_DELETE ( ( BaseType_t ) 5 ) + +#define tmrFIRST_FROM_ISR_COMMAND ( ( BaseType_t ) 6 ) +#define tmrCOMMAND_START_FROM_ISR ( ( BaseType_t ) 6 ) +#define tmrCOMMAND_RESET_FROM_ISR ( ( BaseType_t ) 7 ) +#define tmrCOMMAND_STOP_FROM_ISR ( ( BaseType_t ) 8 ) +#define tmrCOMMAND_CHANGE_PERIOD_FROM_ISR ( ( BaseType_t ) 9 ) + + +/** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an TimerHandle_t variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +struct tmrTimerControl; /* The old naming convention is used to prevent breaking kernel aware debuggers. */ +typedef struct tmrTimerControl * TimerHandle_t; + +/* + * Defines the prototype to which timer callback functions must conform. + */ +typedef void (*TimerCallbackFunction_t)( TimerHandle_t xTimer ); + +/* + * Defines the prototype to which functions used with the + * xTimerPendFunctionCallFromISR() function must conform. + */ +typedef void (*PendedFunction_t)( void *, uint32_t ); + +/** + * TimerHandle_t xTimerCreate( const char * const pcTimerName, + * TickType_t xTimerPeriodInTicks, + * UBaseType_t uxAutoReload, + * void * pvTimerID, + * TimerCallbackFunction_t pxCallbackFunction ); + * + * Creates a new software timer instance, and returns a handle by which the + * created software timer can be referenced. + * + * Internally, within the FreeRTOS implementation, software timers use a block + * of memory, in which the timer data structure is stored. If a software timer + * is created using xTimerCreate() then the required memory is automatically + * dynamically allocated inside the xTimerCreate() function. (see + * http://www.freertos.org/a00111.html). If a software timer is created using + * xTimerCreateStatic() then the application writer must provide the memory that + * will get used by the software timer. xTimerCreateStatic() therefore allows a + * software timer to be created without using any dynamic memory allocation. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a + * timer into the active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer + * by its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick + * periods so the constant portTICK_PERIOD_MS can be used to convert a time that + * has been specified in milliseconds. For example, if the timer must expire + * after 100 ticks, then xTimerPeriodInTicks should be set to 100. + * Alternatively, if the timer must expire after 500ms, then xPeriod can be set + * to ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than or + * equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. + * If uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by TimerCallbackFunction_t, + * which is "void vCallbackFunction( TimerHandle_t xTimer );". + * + * @return If the timer is successfully created then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then NULL is returned. + * + * Example usage: + * @verbatim + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * TimerHandle_t xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * int32_t lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( TimerHandle_t pxTimer ) + * { + * int32_t lArrayIndex; + * const int32_t xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( int32_t ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * int32_t x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) + TimerHandle_t xTimerCreate( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction ) PRIVILEGED_FUNCTION; +#endif + +/** + * TimerHandle_t xTimerCreateStatic(const char * const pcTimerName, + * TickType_t xTimerPeriodInTicks, + * UBaseType_t uxAutoReload, + * void * pvTimerID, + * TimerCallbackFunction_t pxCallbackFunction, + * StaticTimer_t *pxTimerBuffer ); + * + * Creates a new software timer instance, and returns a handle by which the + * created software timer can be referenced. + * + * Internally, within the FreeRTOS implementation, software timers use a block + * of memory, in which the timer data structure is stored. If a software timer + * is created using xTimerCreate() then the required memory is automatically + * dynamically allocated inside the xTimerCreate() function. (see + * http://www.freertos.org/a00111.html). If a software timer is created using + * xTimerCreateStatic() then the application writer must provide the memory that + * will get used by the software timer. xTimerCreateStatic() therefore allows a + * software timer to be created without using any dynamic memory allocation. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a + * timer into the active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer + * by its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick + * periods so the constant portTICK_PERIOD_MS can be used to convert a time that + * has been specified in milliseconds. For example, if the timer must expire + * after 100 ticks, then xTimerPeriodInTicks should be set to 100. + * Alternatively, if the timer must expire after 500ms, then xPeriod can be set + * to ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than or + * equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. + * If uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by TimerCallbackFunction_t, + * which is "void vCallbackFunction( TimerHandle_t xTimer );". + * + * @param pxTimerBuffer Must point to a variable of type StaticTimer_t, which + * will be then be used to hold the software timer's data structures, removing + * the need for the memory to be allocated dynamically. + * + * @return If the timer is created then a handle to the created timer is + * returned. If pxTimerBuffer was NULL then NULL is returned. + * + * Example usage: + * @verbatim + * + * // The buffer used to hold the software timer's data structure. + * static StaticTimer_t xTimerBuffer; + * + * // A variable that will be incremented by the software timer's callback + * // function. + * UBaseType_t uxVariableToIncrement = 0; + * + * // A software timer callback function that increments a variable passed to + * // it when the software timer was created. After the 5th increment the + * // callback function stops the software timer. + * static void prvTimerCallback( TimerHandle_t xExpiredTimer ) + * { + * UBaseType_t *puxVariableToIncrement; + * BaseType_t xReturned; + * + * // Obtain the address of the variable to increment from the timer ID. + * puxVariableToIncrement = ( UBaseType_t * ) pvTimerGetTimerID( xExpiredTimer ); + * + * // Increment the variable to show the timer callback has executed. + * ( *puxVariableToIncrement )++; + * + * // If this callback has executed the required number of times, stop the + * // timer. + * if( *puxVariableToIncrement == 5 ) + * { + * // This is called from a timer callback so must not block. + * xTimerStop( xExpiredTimer, staticDONT_BLOCK ); + * } + * } + * + * + * void main( void ) + * { + * // Create the software time. xTimerCreateStatic() has an extra parameter + * // than the normal xTimerCreate() API function. The parameter is a pointer + * // to the StaticTimer_t structure that will hold the software timer + * // structure. If the parameter is passed as NULL then the structure will be + * // allocated dynamically, just as if xTimerCreate() had been called. + * xTimer = xTimerCreateStatic( "T1", // Text name for the task. Helps debugging only. Not used by FreeRTOS. + * xTimerPeriod, // The period of the timer in ticks. + * pdTRUE, // This is an auto-reload timer. + * ( void * ) &uxVariableToIncrement, // A variable incremented by the software timer's callback function + * prvTimerCallback, // The function to execute when the timer expires. + * &xTimerBuffer ); // The buffer that will hold the software timer structure. + * + * // The scheduler has not started yet so a block time is not used. + * xReturned = xTimerStart( xTimer, 0 ); + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#if( configSUPPORT_STATIC_ALLOCATION == 1 ) + TimerHandle_t xTimerCreateStatic( const char * const pcTimerName, /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + const TickType_t xTimerPeriodInTicks, + const UBaseType_t uxAutoReload, + void * const pvTimerID, + TimerCallbackFunction_t pxCallbackFunction, + StaticTimer_t *pxTimerBuffer ) PRIVILEGED_FUNCTION; +#endif /* configSUPPORT_STATIC_ALLOCATION */ + +/** + * void *pvTimerGetTimerID( TimerHandle_t xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer, and by calling the + * vTimerSetTimerID() API function. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used as time specific (timer local) storage. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( const TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** + * void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ); + * + * Sets the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used as time specific (timer local) storage. + * + * @param xTimer The timer being updated. + * + * @param pvNewID The ID to assign to the timer. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) PRIVILEGED_FUNCTION; + +/** + * BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired one-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * @verbatim + * // This function assumes xTimer has already been created. + * void vAFunction( TimerHandle_t xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + * @endverbatim + */ +BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** + * TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ); + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ) PRIVILEGED_FUNCTION; + +/** + * BaseType_t xTimerStart( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xTicksToWait is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerStop( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xTicksToWait is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerChangePeriod( TimerHandle_t xTimer, + * TickType_t xNewPeriod, + * TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xTicksToWait is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xTicksToWait ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( TimerHandle_t xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_PERIOD_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + * @endverbatim + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerDelete( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xTicksToWait is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerReset( TimerHandle_t xTimer, TickType_t xTicksToWait ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * through a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xTicksToWait Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xTicksToWait is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xTicksToWait ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * @verbatim + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * TimerHandle_t xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * int32_t x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_PERIOD_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * vTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + * @endverbatim + */ +#define xTimerReset( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) ) + +/** + * BaseType_t xTimerStartFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerStopFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP_FROM_ISR, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerChangePeriodFromISR( TimerHandle_t xTimer, + * TickType_t xNewPeriod, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD_FROM_ISR, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * BaseType_t xTimerResetFromISR( TimerHandle_t xTimer, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * @verbatim + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( TimerHandle_t pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * BaseType_t xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used). + * } + * } + * @endverbatim + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + + +/** + * BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, + * void *pvParameter1, + * uint32_t ulParameter2, + * BaseType_t *pxHigherPriorityTaskWoken ); + * + * + * Used from application interrupt service routines to defer the execution of a + * function to the RTOS daemon task (the timer service task, hence this function + * is implemented in timers.c and is prefixed with 'Timer'). + * + * Ideally an interrupt service routine (ISR) is kept as short as possible, but + * sometimes an ISR either has a lot of processing to do, or needs to perform + * processing that is not deterministic. In these cases + * xTimerPendFunctionCallFromISR() can be used to defer processing of a function + * to the RTOS daemon task. + * + * A mechanism is provided that allows the interrupt to return directly to the + * task that will subsequently execute the pended callback function. This + * allows the callback function to execute contiguously in time with the + * interrupt - just as if the callback had executed in the interrupt itself. + * + * @param xFunctionToPend The function to execute from the timer service/ + * daemon task. The function must conform to the PendedFunction_t + * prototype. + * + * @param pvParameter1 The value of the callback function's first parameter. + * The parameter has a void * type to allow it to be used to pass any type. + * For example, unsigned longs can be cast to a void *, or the void * can be + * used to point to a structure. + * + * @param ulParameter2 The value of the callback function's second parameter. + * + * @param pxHigherPriorityTaskWoken As mentioned above, calling this function + * will result in a message being sent to the timer daemon task. If the + * priority of the timer daemon task (which is set using + * configTIMER_TASK_PRIORITY in FreeRTOSConfig.h) is higher than the priority of + * the currently running task (the task the interrupt interrupted) then + * *pxHigherPriorityTaskWoken will be set to pdTRUE within + * xTimerPendFunctionCallFromISR(), indicating that a context switch should be + * requested before the interrupt exits. For that reason + * *pxHigherPriorityTaskWoken must be initialised to pdFALSE. See the + * example code below. + * + * @return pdPASS is returned if the message was successfully sent to the + * timer daemon task, otherwise pdFALSE is returned. + * + * Example usage: + * @verbatim + * + * // The callback function that will execute in the context of the daemon task. + * // Note callback functions must all use this same prototype. + * void vProcessInterface( void *pvParameter1, uint32_t ulParameter2 ) + * { + * BaseType_t xInterfaceToService; + * + * // The interface that requires servicing is passed in the second + * // parameter. The first parameter is not used in this case. + * xInterfaceToService = ( BaseType_t ) ulParameter2; + * + * // ...Perform the processing here... + * } + * + * // An ISR that receives data packets from multiple interfaces + * void vAnISR( void ) + * { + * BaseType_t xInterfaceToService, xHigherPriorityTaskWoken; + * + * // Query the hardware to determine which interface needs processing. + * xInterfaceToService = prvCheckInterfaces(); + * + * // The actual processing is to be deferred to a task. Request the + * // vProcessInterface() callback function is executed, passing in the + * // number of the interface that needs processing. The interface to + * // service is passed in the second parameter. The first parameter is + * // not used in this case. + * xHigherPriorityTaskWoken = pdFALSE; + * xTimerPendFunctionCallFromISR( vProcessInterface, NULL, ( uint32_t ) xInterfaceToService, &xHigherPriorityTaskWoken ); + * + * // If xHigherPriorityTaskWoken is now set to pdTRUE then a context + * // switch should be requested. The macro used is port specific and will + * // be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() - refer to + * // the documentation page for the port being used. + * portYIELD_FROM_ISR( xHigherPriorityTaskWoken ); + * + * } + * @endverbatim + */ +BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; + + /** + * BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, + * void *pvParameter1, + * uint32_t ulParameter2, + * TickType_t xTicksToWait ); + * + * + * Used to defer the execution of a function to the RTOS daemon task (the timer + * service task, hence this function is implemented in timers.c and is prefixed + * with 'Timer'). + * + * @param xFunctionToPend The function to execute from the timer service/ + * daemon task. The function must conform to the PendedFunction_t + * prototype. + * + * @param pvParameter1 The value of the callback function's first parameter. + * The parameter has a void * type to allow it to be used to pass any type. + * For example, unsigned longs can be cast to a void *, or the void * can be + * used to point to a structure. + * + * @param ulParameter2 The value of the callback function's second parameter. + * + * @param xTicksToWait Calling this function will result in a message being + * sent to the timer daemon task on a queue. xTicksToWait is the amount of + * time the calling task should remain in the Blocked state (so not using any + * processing time) for space to become available on the timer queue if the + * queue is found to be full. + * + * @return pdPASS is returned if the message was successfully sent to the + * timer daemon task, otherwise pdFALSE is returned. + * + */ +BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +/** + * const char * const pcTimerGetName( TimerHandle_t xTimer ); + * + * Returns the name that was assigned to a timer when the timer was created. + * + * @param xTimer The handle of the timer being queried. + * + * @return The name assigned to the timer specified by the xTimer parameter. + */ +const char * pcTimerGetName( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */ + +/** + * void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ); + * + * Updates a timer to be either an autoreload timer, in which case the timer + * automatically resets itself each time it expires, or a one shot timer, in + * which case the timer will only expire once unless it is manually restarted. + * + * @param xTimer The handle of the timer being updated. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the timer's period (see the + * xTimerPeriodInTicks parameter of the xTimerCreate() API function). If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + */ +void vTimerSetReloadMode( TimerHandle_t xTimer, const UBaseType_t uxAutoReload ) PRIVILEGED_FUNCTION; + +/** + * TickType_t xTimerGetPeriod( TimerHandle_t xTimer ); + * + * Returns the period of a timer. + * + * @param xTimer The handle of the timer being queried. + * + * @return The period of the timer in ticks. + */ +TickType_t xTimerGetPeriod( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/** +* TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ); +* +* Returns the time in ticks at which the timer will expire. If this is less +* than the current tick count then the expiry time has overflowed from the +* current time. +* +* @param xTimer The handle of the timer being queried. +* +* @return If the timer is running then the time in ticks at which the timer +* will next expire is returned. If the timer is not running then the return +* value is undefined. +*/ +TickType_t xTimerGetExpiryTime( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +BaseType_t xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION; + +#if( configUSE_TRACE_FACILITY == 1 ) + void vTimerSetTimerNumber( TimerHandle_t xTimer, UBaseType_t uxTimerNumber ) PRIVILEGED_FUNCTION; + UBaseType_t uxTimerGetTimerNumber( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/lib/FreeRTOS-SAMD51/wrapping memory functions/platform.local.txt b/lib/FreeRTOS-SAMD51/wrapping memory functions/platform.local.txt new file mode 100644 index 0000000..0973646 --- /dev/null +++ b/lib/FreeRTOS-SAMD51/wrapping memory functions/platform.local.txt @@ -0,0 +1,49 @@ +####################################################################### +# For wrapping freertos malloc/free/realloc/calloc functions +####################################################################### +# Description: + +# This linker setting change will allow all microcontroller malloc/free/realloc/calloc +# operations to be managed by FreeRtos. This could eliminate memory corruption issues on +# c++ intensive projects, or projects that might be fragmenting the heap. + +####################################################################### +# Setup Arduino IDE: + +# Copy this file (platform.local.txt) to the same directory as the already existing platform.txt file you want to override with these compiler settings. + +# Example: To add this feature to a sparkfun samd21 board, put the file in this location +# C:\Users\UserName\AppData\Local\Arduino15\packages\SparkFun\hardware\samd\1.5.4 + +# Example: To add this feature to a adafruit m0 board, put the file in this location +# C:\Users\UserName\AppData\Local\Arduino15\packages\adafruit\hardware\samd\1.2.9 + +####################################################################### +# Setup Sloeber IDE: + +# If using Sloaber Ide, the platform.local.txt file is not implemented or recognised. +# Follow the manual setup section instead. + +####################################################################### +# Setup Manual: + +# If you want wrap the `malloc`, `free`, `realloc` and `calloc` system functions with those provided by FreeRTOS, simply use the *--wrap* option +# passed to the gcc linker, by appending the following line to the `compiler.ldflags=` line of the [**platform.txt**](https://github.com/arduino/ArduinoCore-samd/blob/master/platform.txt) file: +# -Wl,--wrap=malloc -Wl,--wrap=free -Wl,--wrap=calloc -Wl,--wrap=realloc + + +####################################################################### +# Compiling Non FreeRtos Arduino Projects + +# These compiler flags will only work for FreeRtos arduino projects. Compiling a basic (Non FreeRtos) arduino project will give you compiler errors saying: +undefined reference to `__wrap_malloc' +undefined reference to `__wrap_free' + +# In order to compile a normal arduino project again: +# A) Remove or rename platform.local.txt. I usually rename it to platform.local.txt.disabled so I can turn the feature back on at a later date. +# B) If you performed manual setup, remove the added linker options. + +####################################################################### +# Override compiler setting + +compiler.ldflags=-mcpu={build.mcu} -mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--wrap=malloc -Wl,--wrap=free -Wl,--wrap=calloc -Wl,--wrap=realloc diff --git a/lib/ICM-20948/.gitattributes b/lib/ICM-20948/.gitattributes new file mode 100644 index 0000000..dfe0770 --- /dev/null +++ b/lib/ICM-20948/.gitattributes @@ -0,0 +1,2 @@ +# Auto detect text files and perform LF normalization +* text=auto diff --git a/lib/ICM-20948/.gitignore b/lib/ICM-20948/.gitignore new file mode 100644 index 0000000..535de7b --- /dev/null +++ b/lib/ICM-20948/.gitignore @@ -0,0 +1,2 @@ +# VSCode +*.vscode* diff --git a/lib/ICM-20948/CONTRIBUTING.md b/lib/ICM-20948/CONTRIBUTING.md new file mode 100644 index 0000000..ebe137b --- /dev/null +++ b/lib/ICM-20948/CONTRIBUTING.md @@ -0,0 +1,20 @@ +# How to Contribute + +Thank you so *much* for offering to help out. We truly appreciate it. + +If you'd like to contribute, start by searching through the [issues](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/issues) and [pull requests](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/pulls) to see whether someone else has raised a similar idea or question. +Please check the [closed issues](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/issues?q=is%3Aissue+is%3Aclosed) +and [closed pull requests](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/pulls?q=is%3Apr+is%3Aclosed) too - you may find that your issue or feature has already been discussed. + +If you decide to add a feature to this library, please create a PR and follow these best practices: + +* Change as little as possible. Do not submit a PR that changes 100 lines of whitespace. Break up into multiple PRs if necessary. +* If you've added a new feature document it with a simple example sketch. This serves both as a test of your PR and as a quick way for users to quickly learn how to use your new feature. +* If you add new functions also add them to _keywords.txt_ so that they are properly highlighted in Arduino. [Read more](https://www.arduino.cc/en/Hacking/libraryTutorial). +* **Important:** Please submit your PR using the [release_candidate branch](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/tree/release_candidate). That way, we can merge and test your PR quickly without changing the _master_ branch + +![Contributing.JPG](./img/Contributing.JPG) + +## Style guide + +Please read and follow the [Arduino API style guide](https://www.arduino.cc/en/Reference/APIStyleGuide). Also read and consider the [Arduino style guide](https://www.arduino.cc/en/Reference/StyleGuide). diff --git a/lib/ICM-20948/DMP.md b/lib/ICM-20948/DMP.md new file mode 100644 index 0000000..bc03252 --- /dev/null +++ b/lib/ICM-20948/DMP.md @@ -0,0 +1,2436 @@ +# InvenSense Digital Motion Processor (DMP™) + +## What is the Digital Motion Processor (DMP™)? + +In version 1.2 of this library, we added _partial_ support for the InvenSense Digital Motion Processor (DMP™). The DMP is firmware which runs on the +ICM-20948 and which "offloads computation of motion processing algorithms from the host processor, improving system power performance". + +"The DMP enables ultra-low power run-time and background calibration of the accelerometer, gyroscope, and compass, maintaining optimal performance of +the sensor data for both physical and virtual sensors generated through sensor fusion." + +The DMP allows the accelerometer, gyro and magnetometer data to be combined (fused) so that Quaternion data can be produced. + +The DMP firmware binary has been available for quite some time. It is included in InvenSense's "MotionLink" and "Embedded Motion Driver (eMD)" examples +which can be downloaded from the InvenSense Developers Corner. However, the code is opaque and difficult to follow. + +Users like [@ericalbers](https://github.com/ericalbers/ICM20948_DMP_Arduino) and [@ZaneL](https://github.com/ZaneL/Teensy-ICM-20948) have ported the +InvenSense example code to the Arduino environment previously. We are grateful to Eric and Zane as their code allowed us to reverse-engineer some of the +ICM-20948 configuration steps. + +We are also grateful to InvenSense themselves for sharing with us a _confidential & proprietary_ document called "_Application Note: Programming Sequence for +ICM-20648 DMP Hardware Function_". InvenSense admit that the document is not complete and have asked us not to share it openly. + +The InvenSense document and the bus traffic we captured using Zane's port have allowed us to add _partial_ support for the DMP to this library, using our +own functions. We say _partial_ because, at the time of writing, our library does not support: activity recognition, step counting, pick-up and tap-detection. +It does however support: +- Raw and calibrated accelerometer, gyro and compass data and accuracy +- 6-axis and 9-axis Quaternion data (including Game Rotation Vector data) +- Geomagnetic Rotation Vector data +- and [more...](#which-dmp-features-are-currently-supported) + +We have added [five new examples](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/tree/master/examples/Arduino) to show how to configure the DMP and read: +9-axis Quaternion data; 6-axis Quaternion converted to Euler angles (roll, pitch & yaw); raw accelerometer data. + +## Is DMP support enabled by default? + +No. The DMP occupies 14kBytes of program memory and so, to allow the library to continue to run on processors with limited memory, DMP support is disabled by default. + +You can enable it by editing the file called ```ICM_20948_C.h``` and uncommenting [line 29](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/blob/master/src/util/ICM_20948_C.h#L29): + +Change: + +``` +//#define ICM_20948_USE_DMP +``` + +to: + +``` +#define ICM_20948_USE_DMP +``` + +You will find ```ICM_20948_C.h``` in the library _src\util_ folder. If you are using Windows, you will find it in _Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util_. + +## How is the DMP loaded and started? + +In version 1.2.5 we added a new helper function named ```initializeDMP```. This is a weak function which you can overwrite e.g. if you want to change the sample rate +(see [Example10](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/blob/master/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino) for details). +```initializeDMP``` does most of the heavy lifting for you: it downloads the DMP firmware; and configures all of the registers with the appropriate values. The only things +you need to do manually are: select which DMP sensors to enable; reset and start both FIFO and DMP. + +The DMP firmware is loaded into the ICM-20948's processor memory space via three special Bank 0 registers: +- **AGB0_REG_MEM_START_ADDR** (0x7C) - the address which AGB0_REG_MEM_R_W reads from or writes to (it auto-increments after each read or write) +- **AGB0_REG_MEM_R_W** (0x7D) - the memory read/write register +- **AGB0_REG_MEM_BANK_SEL** (0x7E) - the memory bank select. The complete read/write address is: (AGB0_REG_MEM_BANK_SEL * 256) + AGB0_REG_MEM_START_ADDR + +The firmware binary (14290 or 14301 Bytes) is written into processor memory starting at address 0x90. ```loadDMPFirmware``` automatically breaks the code up into 256 byte blocks and increments +**AGB0_REG_MEM_BANK_SEL** during the writing. + +Before the DMP is enabled, the 16-bit register **AGB2_REG_PRGM_START_ADDRH** (Bank 2, 0x50) needs to be loaded with the program start address. ```setDMPstartAddress``` does this for you. + +The DMP is enabled or reset by setting bits in the Bank 0 register **AGB0_REG_USER_CTRL** (0x03). ```enableDMP``` and ```resetDMP``` do this for you. + +The helper functions ```readDMPmems``` and ```writeDMPmems``` will let you read and write data directly from the DMP memory space. + +## How do I access the DMP data? + +The DMP data is returned via the FIFO (First In First Out). ```readDMPdataFromFIFO``` checks if any data is present in the FIFO (by calling ```getFIFOcount``` which reads the 16-bit register +**AGB0_REG_FIFO_COUNT_H** (0x70)). If data is present, it is copied into a ```icm_20948_DMP_data_t``` struct. + +```readDMPdataFromFIFO``` will return: +- ```ICM_20948_Stat_FIFONoDataAvail``` if no data or incomplete data is available +- ```ICM_20948_Stat_Ok``` if a valid frame was read +- ```ICM_20948_Stat_FIFOMoreDataAvail``` if a valid frame was read _and_ the FIFO contains more (unread) data +- ```ICM_20948_Stat_FIFOIncompleteData``` if a frame was present in the FIFO but it was incomplete + +You can examine the 16-bit ```icm_20948_DMP_data_t data.header``` to see what data the frame contained. ```data.header``` is a bit field; each bit indicates what data is present: +- **DMP_header_bitmap_Compass_Calibr** (0x0020) +- **DMP_header_bitmap_Gyro_Calibr** (0x0040) +- **DMP_header_bitmap_Geomag** (0x0100) +- **DMP_header_bitmap_PQuat6** (0x0200) +- **DMP_header_bitmap_Quat9** (0x0400) +- **DMP_header_bitmap_Quat6** (0x0800) +- **DMP_header_bitmap_ALS** (0x1000) +- **DMP_header_bitmap_Compass** (0x2000) +- **DMP_header_bitmap_Gyro** (0x4000) +- **DMP_header_bitmap_Accel** (0x8000) + +**DMP_header_bitmap_Header2** (0x0008) indicates if any secondary data was included. If the **DMP_header_bitmap_Header2** bit is set, the frame also contained one or more of: +- **DMP_header2_bitmap_Compass_Accuracy** (0x1000) +- **DMP_header2_bitmap_Gyro_Accuracy** (0x2000) +- **DMP_header2_bitmap_Accel_Accuracy** (0x4000) + +## Which DMP features are currently supported? + +All of the following _should_ work, but we have not tested them all: + +``` +INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) +INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) +INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) +INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) +INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) +INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) +INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) +INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) +INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) +INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) +INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) +INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) +INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) +INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) +INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) +``` + +## What changes did you make in v1.2.5? + +In v1.2.5 we added some critical missing configuration steps: +- We use I2C_SLV0 and I2C_SLV1 to request the magnetometer data and trigger the next Single Measurement. We no longer use the 100Hz continuous mode for the DMP +- We now read ten bytes of data from the magnetometer, starting at register 0x03; instead of reading nine bytes, starting at register 0x10 + - Register 0x03 is reserved and the other nine registers are undocumented. They appear to contain the raw magnetometer reading in big-endian format (instead of little-endian) + - We had to dig deep into InvenSense's Icm20948AuxCompassAkm.c to find this out... +- We configure the I2C Master ODR which reduces the magnetometer read rate from a silly 1100Hz to a sensible 69Hz + - We had to monitor the Aux I2C pins and study the AK09916 traffic to figure this out... + +The DMP configuration code was becoming so verbose that we decided to move it into its own function called ```initializeDMP```. This is a weak function which you can overwrite +e.g. if you want to change the sample rate +(see [Example10](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/blob/master/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino) for details). +```initializeDMP``` does most of the heavy lifting for you: it downloads the DMP firmware; and configures all of the registers with the appropriate values. The only things +you need to do manually are: select which DMP sensors to enable; reset and start both FIFO and DMP. Please see the revised DMP examples for more details. + +## What changes did you make in v1.2.6? + +The final piece of the DMP puzzle turned out to be that the accel and gyro must not be in low power mode when using the DMP. The InvenSense code puts the I2C Controller, +the accel and the gyro into low power mode initially; our library did the same thing. But we had missed that the code then changes its mind and leaves only the I2C Controller +in low power mode. This subtle detail is what was preventing the DMP from working correctly. (It took us _weeks_ to find this!) + +## Where are the DMP registers defined? + +You will find the definitions in ```ICM_20948_DMP.h```. + +That file also includes the definition for the ```icm_20948_DMP_data_t``` struct which is loaded with DMP data from the FIFO. + +```const int``` declarations (including the DMP firmware image) are in ```ICM_20948_C.c``` + +## Can the DMP generate interrupts? + +Yes it can, but you might find that they are not fully supported as we have not tested them. The main functions you will need to experiment with are ```intEnableDMP``` and ```enableDMPSensorInt```. + +## How is the DMP data rate set? + +It is a _combination_ of the raw sensor rate (set by ```setSampleRate```) and the multiple DMP Output Data Rate (ODR) registers +(set by ```setDMPODRrate```). There are other settings that need to be changed to match the sample rate too. +Please see [examples 9 & 10](https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/tree/master/examples/Arduino) for more details. + +The DMP is capable of outputting multiple sensor data at different rates to the FIFO. + +## Can I contribute to this library? + +Absolutely! Please see [CONTRIBUTING.md](./CONTRIBUTING.md) for further details. + +## Can I see the full DMP configuration captured from @ZaneL 's Teensy-ICM-20948 code? + +Brace yourself. Here it is. ZaneL's code defaults to using the Game Rotation Vector (Quat6) at 225Hz and - by default - does not start the magnetometer. +So you won't see the I2C Controller configuration traffic here. + +- **...** indicates where I've omitted some of the bus transactions (e.g. the bulk of the firmware upload) + +``` +SPI Traffic captured using ZaneL's Teensy-ICM-20948 wrapper for the InvenSense Nucleo example: +https://github.com/ZaneL/Teensy-ICM-20948 + +QuaternionAnimation (Quat6): + .enable_gyroscope = false, // Enables gyroscope output + .enable_accelerometer = false, // Enables accelerometer output + .enable_magnetometer = false, // Enables magnetometer output + .enable_quaternion = true, // Enables quaternion output + .gyroscope_frequency = 1, // Max frequency = 225, min frequency = 1 + .accelerometer_frequency = 1, // Max frequency = 225, min frequency = 1 + .magnetometer_frequency = 1, // Max frequency = 70, min frequency = 1 + .quaternion_frequency = 225 // Max frequency = 225, min frequency = 50 + + + + +617669-617713 SPI: COPI data: 80 : Read Bank 0 Reg 0x00 WHO_AM_I +617711-617755 SPI: CIPO data: EA : ICM_20948 + +617952-617994 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +617994-618036 SPI: COPI data: 01 : Clock Source Auto (Best Available) + +618291-618333 SPI: COPI data: 83 : Read Bank 0 Reg 0x03 USER_CTRL +618333-618375 SPI: COPI data: 00 + +618426-618468 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +618468-618510 SPI: COPI data: 10 : I2C_IF_DIS Reset I2C peripheral module and put the serial interface in SPI mode only + +618560-618602 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +618602-618644 SPI: COPI data: 47 : Disable pressure sensor. Disable all gyroscope axes + +618695-618737 SPI: COPI data: 80 : Read Bank 0 Reg 0x00 WHO_AM_I +618737-618779 SPI: CIPO data: EA : ICM_20948 + +618830-618872 SPI: COPI data: 05 : Write Bank 0 Reg 0x05 LP_CONFIG +618872-618914 SPI: COPI data: 70 : Operate I2C controller, accel and gyro in duty cycled mode + +618963-619007 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +619005-619049 SPI: COPI data: 10 : I2C_IF_DIS Reset I2C peripheral module and put the serial interface in SPI mode only + + + +619098-619140 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +619140-619182 SPI: COPI data: 90 : Memory Address 0x90 : Start of the DMP + +619225-619269 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +619267-619311 SPI: COPI data: 00 : DMP firmware (16 bytes) +619310-619352 SPI: COPI data: 01 +619352-619394 SPI: COPI data: 00 +619394-619436 SPI: COPI data: 00 +619436-619478 SPI: COPI data: 00 +619478-619520 SPI: COPI data: 00 +619520-619562 SPI: COPI data: 00 +619562-619604 SPI: COPI data: 00 +619604-619646 SPI: COPI data: 00 +619646-619688 SPI: COPI data: 00 +619688-619730 SPI: COPI data: 00 +619730-619772 SPI: COPI data: 00 +619772-619814 SPI: COPI data: 00 +619814-619856 SPI: COPI data: 00 +619856-619898 SPI: COPI data: 00 +619898-619940 SPI: COPI data: 00 + +619988-620032 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +620030-620074 SPI: COPI data: A0 : Memory Address 0xA0 : DMP + +620116-620158 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +620158-620200 SPI: COPI data: 00 : DMP firmware (16 bytes) +620200-620242 SPI: COPI data: 05 +620242-620284 SPI: COPI data: 00 +620284-620326 SPI: COPI data: 00 +620326-620370 SPI: COPI data: 00 +620368-620412 SPI: COPI data: 05 +620410-620454 SPI: COPI data: 00 +620452-620496 SPI: COPI data: 00 +620494-620538 SPI: COPI data: 00 +620536-620580 SPI: COPI data: 05 +620578-620622 SPI: COPI data: 00 +620620-620664 SPI: COPI data: 01 +620662-620706 SPI: COPI data: 00 +620704-620748 SPI: COPI data: 05 +620746-620790 SPI: COPI data: 00 +620788-620832 SPI: COPI data: FF + +... + +625336-625380 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +625378-625422 SPI: COPI data: 01 : Bank 0x01 + +625464-625508 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +625506-625550 SPI: COPI data: 00 : Memory Address 0x00 : DMP + +625592-625634 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +625634-625676 SPI: COPI data: 00 : DMP firmware (16 bytes) +625676-625718 SPI: COPI data: 00 +625718-625760 SPI: COPI data: 03 +625760-625802 SPI: COPI data: 84 +625802-625844 SPI: COPI data: 00 +625844-625886 SPI: COPI data: 00 +625886-625928 SPI: COPI data: 9C +625928-625970 SPI: COPI data: 40 +625970-626012 SPI: COPI data: 00 +626012-626054 SPI: COPI data: 00 +626054-626096 SPI: COPI data: 00 +626096-626138 SPI: COPI data: 00 +626138-626180 SPI: COPI data: 04 +626180-626222 SPI: COPI data: 00 +626222-626264 SPI: COPI data: 00 +626264-626306 SPI: COPI data: 00 + +... + +1416262-1416304 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +1416304-1416346 SPI: COPI data: 38 : Bank 0x38 + +1416390-1416432 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +1416432-1416474 SPI: COPI data: 00 : Memory Address 0x00 : DMP + +1416518-1416560 SPI: COPI data: 7D : DMP firmware (16 bytes) +1416560-1416602 SPI: COPI data: DA +1416602-1416644 SPI: COPI data: DE +1416644-1416686 SPI: COPI data: F5 +1416686-1416728 SPI: COPI data: E2 +1416728-1416770 SPI: COPI data: F0 +1416770-1416812 SPI: COPI data: D9 +1416812-1416854 SPI: COPI data: F8 +1416854-1416896 SPI: COPI data: D8 +1416896-1416938 SPI: COPI data: A9 +1416938-1416980 SPI: COPI data: F3 +1416980-1417022 SPI: COPI data: F9 +1417022-1417064 SPI: COPI data: F9 +1417064-1417106 SPI: COPI data: F9 +1417106-1417148 SPI: COPI data: F9 +1417148-1417190 SPI: COPI data: F9 +1417190-1417232 SPI: COPI data: F9 + +... + +1421735-1421777 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +1421777-1421819 SPI: COPI data: 60 : Memory Address 0x60 : DMP + +1421862-1421906 SPI: COPI data: 7D : DMP firmware (13 bytes) +1421904-1421948 SPI: COPI data: F3 +1421946-1421990 SPI: COPI data: CD +1421988-1422032 SPI: COPI data: F2 +1422030-1422074 SPI: COPI data: CA +1422072-1422116 SPI: COPI data: D0 +1422114-1422158 SPI: COPI data: F3 +1422156-1422200 SPI: COPI data: CB +1422198-1422242 SPI: COPI data: F2 +1422240-1422284 SPI: COPI data: C8 +1422282-1422326 SPI: COPI data: D0 +1422324-1422368 SPI: COPI data: F3 +1422366-1422410 SPI: COPI data: C9 +1422408-1422452 SPI: COPI data: E0 + + + +1422500-1422542 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +1422542-1422584 SPI: COPI data: 00 : Bank 0x00 + +1422628-1422672 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +1422670-1422714 SPI: COPI data: 90 : Memory Address 0x90 : Start of the DMP + +1422756-1422800 SPI: COPI data: FD : Read Bank 0 Reg 0x7D Memory Read/Write +1422798-1422842 SPI: CIPO data: 00 : DMP firmware (16 bytes) +1422840-1422884 SPI: CIPO data: 01 +1422882-1422926 SPI: CIPO data: 00 +1422924-1422968 SPI: CIPO data: 00 +1422966-1423010 SPI: CIPO data: 00 +1423008-1423052 SPI: CIPO data: 00 +1423050-1423094 SPI: CIPO data: 00 +1423092-1423136 SPI: CIPO data: 00 +1423134-1423178 SPI: CIPO data: 00 +1423176-1423220 SPI: CIPO data: 00 +1423218-1423262 SPI: CIPO data: 00 +1423260-1423304 SPI: CIPO data: 00 +1423302-1423346 SPI: CIPO data: 00 +1423344-1423388 SPI: CIPO data: 00 +1423386-1423430 SPI: CIPO data: 00 +1423428-1423472 SPI: CIPO data: 00 + +1423529-1423571 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +1423571-1423613 SPI: COPI data: A0 : Memory Address 0xA0 : DMP + +1423657-1423701 SPI: COPI data: FD : Read Bank 0 Reg 0x7D Memory Read/Write +1423699-1423743 SPI: CIPO data: 00 : DMP firmware (16 bytes) +1423741-1423785 SPI: CIPO data: 05 +1423783-1423827 SPI: CIPO data: 00 +1423825-1423869 SPI: CIPO data: 00 +1423867-1423911 SPI: CIPO data: 00 +1423909-1423953 SPI: CIPO data: 05 +1423951-1423995 SPI: CIPO data: 00 +1423993-1424037 SPI: CIPO data: 00 +1424035-1424079 SPI: CIPO data: 00 +1424077-1424121 SPI: CIPO data: 05 +1424119-1424163 SPI: CIPO data: 00 +1424161-1424205 SPI: CIPO data: 01 +1424203-1424247 SPI: CIPO data: 00 +1424245-1424289 SPI: CIPO data: 05 +1424287-1424331 SPI: CIPO data: 00 +1424329-1424373 SPI: CIPO data: FF + +... + +2228746-2228790 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2228788-2228832 SPI: COPI data: 38 : Bank 0x38 + +2228874-2228917 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2228917-2228959 SPI: COPI data: 00 : Memory Address 0x00 : DMP + +2229003-2229045 SPI: COPI data: FD : Read Bank 0 Reg 0x7D Memory Read/Write +2229045-2229087 SPI: CIPO data: DA : DMP firmware (16 bytes) +2229087-2229129 SPI: CIPO data: DE +2229129-2229171 SPI: CIPO data: F5 +2229171-2229213 SPI: CIPO data: E2 +2229213-2229255 SPI: CIPO data: F0 +2229255-2229297 SPI: CIPO data: D9 +2229297-2229339 SPI: CIPO data: F8 +2229339-2229381 SPI: CIPO data: D8 +2229381-2229423 SPI: CIPO data: A9 +2229423-2229465 SPI: CIPO data: F3 +2229465-2229507 SPI: CIPO data: F9 +2229507-2229549 SPI: CIPO data: F9 +2229549-2229591 SPI: CIPO data: F9 +2229591-2229633 SPI: CIPO data: F9 +2229633-2229675 SPI: CIPO data: F9 +2229675-2229717 SPI: CIPO data: F9 + +... + +2234280-2234322 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2234322-2234364 SPI: COPI data: 60 : Memory Address 0x60 : DMP + +2234408-2234450 SPI: COPI data: FD : Read Bank 0 Reg 0x7D Memory Read/Write +2234450-2234492 SPI: CIPO data: F3 : DMP firmware (13 bytes) +2234492-2234534 SPI: CIPO data: CD +2234534-2234576 SPI: CIPO data: F2 +2234576-2234618 SPI: CIPO data: CA +2234618-2234660 SPI: CIPO data: D0 +2234660-2234702 SPI: CIPO data: F3 +2234702-2234744 SPI: CIPO data: CB +2234744-2234786 SPI: CIPO data: F2 +2234786-2234828 SPI: CIPO data: C8 +2234828-2234870 SPI: CIPO data: D0 +2234870-2234912 SPI: CIPO data: F3 +2234912-2234954 SPI: CIPO data: C9 +2234954-2234996 SPI: CIPO data: E0 + + + +2235055-2235097 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2235097-2235139 SPI: CIPO data: 00 + +2235183-2235225 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2235225-2235267 SPI: COPI data: 20 : Select Bank 2 + +2235311-2235355 SPI: COPI data: 50 : Write Bank 2 Reg 0x50 PRGM_START_ADDRH +2235353-2235397 SPI: COPI data: 10 : Magic Number 0x1000 +2235395-2235439 SPI: COPI data: 00 + +2235487-2235531 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2235529-2235573 SPI: CIPO data: 20 : Bank 2 is selected + +2235615-2235657 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2235657-2235699 SPI: COPI data: 00 : Select Bank 0 + +2235743-2235787 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2235785-2235829 SPI: COPI data: 00 : Bank 0x00 + +2235871-2235915 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2235913-2235957 SPI: COPI data: 40 : DATA_OUT_CTL1 (4 * 16 + 0) + +2235999-2236041 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2236041-2236083 SPI: COPI data: 00 : Set DATA_OUT_CTL1 to 0x0000 +2236083-2236125 SPI: COPI data: 00 + +2236173-2236217 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2236215-2236259 SPI: COPI data: 42 : DATA_OUT_CTL2 (4 * 16 + 2) + +2236301-2236343 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2236343-2236385 SPI: COPI data: 00 : Set DATA_OUT_CTL2 to 0x0000 +2236385-2236427 SPI: COPI data: 00 + +2236475-2236519 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2236517-2236561 SPI: COPI data: 4C : DATA_INTR_CTL (4 * 16 + 12) + +2236603-2236645 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2236645-2236687 SPI: COPI data: 00 : Set DATA_INTR_CTL to 0x0000 +2236687-2236729 SPI: COPI data: 00 + +2236777-2236821 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2236819-2236863 SPI: COPI data: 4E : MOTION_EVENT_CTL (4 * 16 + 14) + +2236905-2236947 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2236947-2236989 SPI: COPI data: 00 : Set MOTION_EVENT_CTL to 0x0000 +2236989-2237031 SPI: COPI data: 00 + +2237079-2237123 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2237121-2237165 SPI: COPI data: 8A : DATA_RDY_STATUS (8 * 16 + 10) + +2237208-2237250 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2237250-2237292 SPI: COPI data: 00 : Set DATA_RDY_STATUS to 0x0000 +2237292-2237334 SPI: COPI data: 00 + +2237383-2237425 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2237425-2237467 SPI: COPI data: 01 : Bank 0x01 + +2237511-2237553 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2237553-2237595 SPI: COPI data: FE : FIFO_WATERMARK (31 * 16 + 14) + +2237639-2237681 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2237681-2237723 SPI: COPI data: 03 : Set FIFO_WATERMARK to 0x0320 = 800 +2237723-2237765 SPI: COPI data: 20 + +2237814-2237856 SPI: COPI data: 10 : Write Bank 0 Reg 0x10 INT_ENABLE +2237856-2237898 SPI: COPI data: 02 : DMP_INT1_EN : Enable DMP interrupt on pin 1 + +2237947-2237991 SPI: COPI data: 12 : Write Bank 0 Reg 0x12 INT_ENABLE_2 +2237989-2238033 SPI: COPI data: 01 : Enable interrupt for FIFO overflow for peripheral 0 + +2238082-2238124 SPI: COPI data: 26 : Write Bank 0 Reg 0x26 Single FIFO Priority Select +2238124-2238166 SPI: COPI data: E4 : ??? + +2238216-2238260 SPI: COPI data: F5 : Read Bank 0 Reg 0x75 HW Fix Disable +2238258-2238302 SPI: CIPO data: 40 : ICM_20948 returns 0x40 + +2238352-2238394 SPI: COPI data: 75 : Write Bank 0 Reg 0x75 HW Fix Disable +2238394-2238436 SPI: COPI data: 48 : ??? + +2238486-2238528 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2238528-2238570 SPI: CIPO data: 00 : Bank 0 is selected + +2238614-2238656 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2238656-2238698 SPI: COPI data: 20 : Select Bank 2 + +2238742-2238786 SPI: COPI data: 00 : Write Bank 2 Reg 0x00 GYRO_SMPLRT_DIV +2238784-2238828 SPI: COPI data: 13 : Set GYRO_SMPLRT_DIV to 0x13 = 19 + +2238876-2238918 SPI: COPI data: 10 : Write Bank 2 Reg 0x10 ACCEL_SMPLRT_DIV_1 +2238918-2238960 SPI: COPI data: 00 : Set ACCEL_SMPLRT_DIV_1 to 0x0013 = 19 +2238960-2239002 SPI: COPI data: 13 + +2239052-2239096 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2239094-2239138 SPI: CIPO data: 20 : Bank 2 is selected + +2239180-2239224 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2239222-2239266 SPI: COPI data: 00 : Select Bank 0 + +2239309-2239351 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2239351-2239393 SPI: COPI data: 03 : Bank 0x03 + +2239437-2239479 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2239479-2239521 SPI: COPI data: 0A : BAC_RATE (48 * 16 + 10) + +2239564-2239608 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2239606-2239650 SPI: COPI data: 00 : Set BAC_RATE to 0x0000 +2239648-2239692 SPI: COPI data: 00 + +2239740-2239784 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2239782-2239826 SPI: COPI data: 08 : B2S_RATE (48 * 16 + 8) + +2239868-2239910 SPI: COPI data: 7D : Write Bank 0 Reg 0x7D Memory Read/Write +2239910-2239952 SPI: COPI data: 00 : Set B2S_RATE to 0x0000 +2239952-2239994 SPI: COPI data: 00 + +2240041-2240085 SPI: COPI data: 76 : Write Bank 0 Reg 0x76 FIFO_CFG +2240083-2240127 SPI: COPI data: 00 : Set FIFO_CFG to 0x00 + +2240173-2240215 SPI: COPI data: 68 : Write Bank 0 Reg 0x68 FIFO_RST +2240215-2240257 SPI: COPI data: 1F : Set FIFO_RST to 0x1F (Reset the FIFOs for all five peripherals) + +2240305-2240349 SPI: COPI data: 68 : Write Bank 0 Reg 0x68 FIFO_RST +2240347-2240391 SPI: COPI data: 1E : Set FIFO_RST to 0x1E (Reset the FIFOs except peripheral 0) + +2240438-2240480 SPI: COPI data: 66 : Write Bank 0 Reg 0x68 FIFO_EN_1 +2240480-2240522 SPI: COPI data: 00 : Set FIFO_EN_1 to 0x00 + +2240570-2240614 SPI: COPI data: 67 : Write Bank 0 Reg 0x68 FIFO_EN_2 +2240612-2240656 SPI: COPI data: 00 : Set FIFO_EN_2 to 0x00 + +2240702-2240746 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2240744-2240788 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2240834-2240878 SPI: COPI data: 07 : Write Bank 0 Reg 0x06 PWR_MGMT_2 +2240876-2240920 SPI: COPI data: 7F : Set PWR_MGMT_2 : Disable pressure; accel (all axes); gyro (all axes) + +2240966-2241008 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2241008-2241050 SPI: COPI data: 61 : Set PWR_MGMT_1 : Sleep mode; Turn on low power; Auto clock best available + + + +2241319-2241363 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2241361-2241405 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + + + +2241652-2241694 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2241694-2241736 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + + + +2241981-2242025 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2242023-2242067 SPI: CIPO data: 00 : Bank 2 is selected + +2242109-2242151 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2242151-2242193 SPI: COPI data: 30 : Select Bank 3 + +2242237-2242279 SPI: COPI data: 05 : Write Bank 3 Reg 0x05 I2C Peripheral 0 Control +2242279-2242321 SPI: COPI data: 00 : Set I2C_PERIPH0_CTRL to 0x00 + +2242370-2242412 SPI: COPI data: 09 : Write Bank 3 Reg 0x09 I2C Peripheral 1 Control +2242412-2242454 SPI: COPI data: 00 : Set I2C_PERIPH1_CTRL to 0x00 + +2242503-2242545 SPI: COPI data: 0D : Write Bank 3 Reg 0x0D I2C Peripheral 2 Control +2242545-2242587 SPI: COPI data: 00 : Set I2C_PERIPH2_CTRL to 0x00 + +2242636-2242680 SPI: COPI data: 11 : Write Bank 3 Reg 0x11 I2C Peripheral 3 Control +2242678-2242722 SPI: COPI data: 00 : Set I2C_PERIPH3_CTRL to 0x00 + +2242770-2242812 SPI: COPI data: 01 : Write Bank 3 Reg 0x01 I2C Master Control +2242812-2242854 SPI: COPI data: 10 : Set I2C_MST_CTRL to 0x10 : I2C_MST_P_NSR use stop between reads + +2242903-2242945 SPI: COPI data: 00 : Write Bank 3 Reg 0x00 I2C Master ODR Config +2242945-2242987 SPI: COPI data: 04 : Set I2C_MST_ODR_CONFIG to 0x00 : ODR = 1.1kHz + +2243042-2243086 SPI: COPI data: 03 : Write Bank 3 Reg 0x00 I2C Peripheral 0 Address +2243084-2243128 SPI: COPI data: 8C : Set I2C_PERIPH0_ADDR to 0x8C (Read 0x0C AK09916 Magnetometer) + +2243177-2243221 SPI: COPI data: 04 : Write Bank 3 Reg 0x00 I2C Peripheral 0 Register +2243219-2243263 SPI: COPI data: 00 : Point to AK09916 Magnetometer register 0 + +2243312-2243354 SPI: COPI data: 05 : Write Bank 3 Reg 0x05 I2C Peripheral 0 Control +2243354-2243396 SPI: COPI data: 81 : Set I2C_PERIPH0_CTRL to 0x81: Enable reading from peripheral; one byte + +2243447-2243489 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2243489-2243531 SPI: CIPO data: 30 : Bank 3 is selected + +2243574-2243618 SPI: COPI data: 7F : Write Bank 3 Reg 0x7F REG_BANK_SEL +2243616-2243660 SPI: COPI data: 00 : Select Bank 0 + +2243702-2243746 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2243744-2243788 SPI: COPI data: 30 : Set USER_CTRL to 0x30 : Enable I2C Controller module; Reset I2C Peripheral module (SPI mode only) + + + +2364091-2364135 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2364133-2364177 SPI: COPI data: 10 : Set USER_CTRL to 0x10 : Reset I2C Peripheral module (SPI mode only) + +2364226-2364268 SPI: COPI data: BB : Read Bank 0 Reg 0x3B PERIPH_SENS_DATA_00 +2364268-2364310 SPI: CIPO data: 48 : Magnetometer returns 0x48 (Who I Am) + +2364361-2364403 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2364403-2364445 SPI: COPI data: 00 : Bank 0 is selected + +2364489-2364531 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2364531-2364573 SPI: COPI data: 30 : Select Bank 3 + +2364617-2364659 SPI: COPI data: 05 : Write Bank 3 Reg 0x05 I2C Peripheral 0 Control +2364659-2364701 SPI: COPI data: 00 : Set I2C_PERIPH0_CTRL to 0x00 + +2364753-2364797 SPI: COPI data: 07 : Write Bank 3 Reg 0x07 I2C Peripheral 1 Address +2364795-2364839 SPI: COPI data: 0C : Set I2C_PERIPH1_ADDR to 0x0C (Write 0x0C AK09916 Magnetometer) + +2364888-2364930 SPI: COPI data: 08 : Write Bank 3 Reg 0x05 I2C Peripheral 1 Register +2364930-2364972 SPI: COPI data: 31 : Point to AK09916 Magnetometer register 0x31 (CNTL2) + +2365022-2365064 SPI: COPI data: 0A : Write Bank 3 Reg 0x05 I2C Peripheral 1 Data Out +2365064-2365108 SPI: COPI data: 00 + +2365157-2365199 SPI: COPI data: 09 : Write Bank 3 Reg 0x05 I2C Peripheral 1 Control +2365199-2365241 SPI: COPI data: 81 : Enable reading from this peripheral; one byte + +2365291-2365335 SPI: COPI data: FF : Read Bank 3 Reg 0x7F REG_BANK_SEL +2365333-2365377 SPI: CIPO data: 30 : Bank 3 is selected + +2365419-2365461 SPI: COPI data: 7F : Write Bank 3 Reg 0x7F REG_BANK_SEL +2365461-2365503 SPI: COPI data: 00 : Select Bank 0 + +2365547-2365589 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2365589-2365631 SPI: COPI data: 30 : Set USER_CTRL to 0x30 : Enable I2C Controller module; Reset I2C Peripheral module (SPI mode only) + + + +2485926-2485968 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2485968-2486010 SPI: COPI data: 10 : Set USER_CTRL to 0x10 : Reset I2C Peripheral module (SPI mode only) + +2486059-2486103 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2486101-2486145 SPI: COPI data: 00 : Bank 0 is selected + +2486187-2486229 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2486229-2486271 SPI: COPI data: 30 : Select Bank 3 + +2486315-2486357 SPI: COPI data: 09 : Write Bank 3 Reg 0x05 I2C Peripheral 1 Control +2486357-2486399 SPI: COPI data: 00 : Set I2C_PERIPH1_CTRL to 0x00 + +2486449-2486491 SPI: COPI data: 05 : Write Bank 3 Reg 0x05 I2C Peripheral 0 Control +2486491-2486533 SPI: COPI data: 00 : Set I2C_PERIPH0_CTRL to 0x00 + +2486582-2486626 SPI: COPI data: 09 : Write Bank 3 Reg 0x05 I2C Peripheral 1 Control +2486624-2486668 SPI: COPI data: 00 : Set I2C_PERIPH1_CTRL to 0x00 + + + +2486716-2486760 SPI: COPI data: FF : Read Bank 3 Reg 0x7F REG_BANK_SEL +2486758-2486802 SPI: CIPO data: 30 : Bank 3 is selected + +2486844-2486888 SPI: COPI data: 7F : Write Bank 3 Reg 0x7F REG_BANK_SEL +2486886-2486930 SPI: COPI data: 00 : Select Bank 0 + +2486972-2487016 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2487014-2487058 SPI: COPI data: 10 : Set USER_CTRL to 0x10 : Reset I2C Peripheral module (SPI mode only) + +2487144-2487188 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2487186-2487230 SPI: COPI data: 01 : Bank 0x01 + +2487273-2487315 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2487315-2487357 SPI: COPI data: 70 : CPASS_MTX_00 (23 * 16 + 0) + +2487400-2487444 SPI: COPI data: 7D : Set Compass Mount Matrix 00 to 0x09999999 +2487442-2487486 SPI: COPI data: 09 +2487484-2487528 SPI: COPI data: 99 +2487526-2487570 SPI: COPI data: 99 +2487568-2487612 SPI: COPI data: 99 + +2487660-2487702 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2487702-2487744 SPI: COPI data: 74 : CPASS_MTX_01 (23 * 16 + 4) + +2487788-2487830 SPI: COPI data: 7D : Set Compass Mount Matrix 01 to 0x00000000 +2487830-2487872 SPI: COPI data: 00 +2487872-2487914 SPI: COPI data: 00 +2487914-2487956 SPI: COPI data: 00 +2487956-2487998 SPI: COPI data: 00 + +2488048-2488090 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2488090-2488132 SPI: COPI data: 78 : CPASS_MTX_02 (23 * 16 + 8) + +2488175-2488219 SPI: COPI data: 7D : Set Compass Mount Matrix 02 to 0x00000000 +2488217-2488261 SPI: COPI data: 00 +2488259-2488303 SPI: COPI data: 00 +2488301-2488345 SPI: COPI data: 00 +2488343-2488387 SPI: COPI data: 00 + +2488435-2488477 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2488477-2488519 SPI: COPI data: 7C : CPASS_MTX_10 (23 * 16 + 12) + +2488563-2488605 SPI: COPI data: 7D : Set Compass Mount Matrix 10 to 0x00000000 +2488605-2488647 SPI: COPI data: 00 +2488647-2488689 SPI: COPI data: 00 +2488689-2488731 SPI: COPI data: 00 +2488731-2488773 SPI: COPI data: 00 + +2488822-2488866 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2488864-2488907 SPI: COPI data: 80 : CPASS_MTX_11 (24 * 16) + +2488950-2488994 SPI: COPI data: 7D : Set Compass Mount Matrix 11 to 0xF6666667 +2488992-2489036 SPI: COPI data: F6 +2489034-2489078 SPI: COPI data: 66 +2489076-2489120 SPI: COPI data: 66 +2489118-2489162 SPI: COPI data: 67 + +2489210-2489254 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2489252-2489296 SPI: COPI data: 84 : CPASS_MTX_12 (24 * 16 + 4) + +2489338-2489380 SPI: COPI data: 7D : Set Compass Mount Matrix 12 to 0x00000000 +2489380-2489422 SPI: COPI data: 00 +2489422-2489464 SPI: COPI data: 00 +2489464-2489506 SPI: COPI data: 00 +2489506-2489548 SPI: COPI data: 00 + +2489598-2489640 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2489640-2489682 SPI: COPI data: 88 : CPASS_MTX_20 (24 * 16 + 8) + +2489725-2489769 SPI: COPI data: 7D : Set Compass Mount Matrix 20 to 0x00000000 +2489767-2489811 SPI: COPI data: 00 +2489809-2489853 SPI: COPI data: 00 +2489851-2489895 SPI: COPI data: 00 +2489893-2489937 SPI: COPI data: 00 + +2489985-2490029 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2490027-2490071 SPI: COPI data: 8C : CPASS_MTX_21 (24 * 16 + 12) + +2490113-2490155 SPI: COPI data: 7D : Set Compass Mount Matrix 21 to 0x00000000 +2490155-2490197 SPI: COPI data: 00 +2490197-2490239 SPI: COPI data: 00 +2490239-2490281 SPI: COPI data: 00 +2490281-2490323 SPI: COPI data: 00 + +2490373-2490415 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2490415-2490457 SPI: COPI data: 90 : CPASS_MTX_22 (25 * 16) + +2490500-2490544 SPI: COPI data: 7D : Set Compass Mount Matrix 22 to 0xF6666667 +2490542-2490586 SPI: COPI data: F6 +2490584-2490628 SPI: COPI data: 66 +2490626-2490670 SPI: COPI data: 66 +2490668-2490712 SPI: COPI data: 67 + +2490759-2490801 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2490801-2490843 SPI: COPI data: 21 : Set PWR_MGMT_1 : Auto clock best available + + + +2491026-2491070 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2491068-2491112 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + + + + + +2491360-2491402 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2491402-2491444 SPI: COPI data: 0D : Bank 0x0D + +2491488-2491530 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2491530-2491572 SPI: COPI data: 00 : B2S_MTX_00 (208 * 16) + +2491616-2491658 SPI: COPI data: 7D : Set B2S Mount Matrix 00 to 0x40000000 +2491658-2491700 SPI: COPI data: 40 +2491700-2491742 SPI: COPI data: 00 +2491742-2491784 SPI: COPI data: 00 +2491784-2491826 SPI: COPI data: 00 + +2491871-2491915 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2491913-2491957 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2492005-2492047 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2492047-2492089 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + + + +2492335-2492377 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2492377-2492419 SPI: COPI data: 04 : B2S_MTX_01 (208 * 16 + 4) + +2492462-2492506 SPI: COPI data: 7D : Set B2S Mount Matrix 01 to 0x00000000 +2492504-2492548 SPI: COPI data: 00 +2492546-2492590 SPI: COPI data: 00 +2492588-2492632 SPI: COPI data: 00 +2492630-2492674 SPI: COPI data: 00 + +2492718-2492762 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2492760-2492804 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2492851-2492895 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2492893-2492937 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2493182-2493224 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2493224-2493266 SPI: COPI data: 08 : B2S_MTX_02 (208 * 16 + 8) + +2493310-2493352 SPI: COPI data: 7D : Set B2S Mount Matrix 01 to 0x00000000 +2493352-2493394 SPI: COPI data: 00 +2493394-2493436 SPI: COPI data: 00 +2493436-2493478 SPI: COPI data: 00 +2493478-2493520 SPI: COPI data: 00 + +2493565-2493609 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2493607-2493651 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2493698-2493742 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2493740-2493784 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2494029-2494071 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2494071-2494113 SPI: COPI data: 0C : B2S_MTX_10 (208 * 16 + 12) + +2494156-2494200 SPI: COPI data: 7D : Set B2S Mount Matrix 10 to 0x00000000 +2494198-2494242 SPI: COPI data: 00 +2494240-2494284 SPI: COPI data: 00 +2494282-2494326 SPI: COPI data: 00 +2494324-2494368 SPI: COPI data: 00 + +2494412-2494456 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2494454-2494498 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2494545-2494589 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2494587-2494631 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2494876-2494920 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2494918-2494962 SPI: COPI data: 10 : B2S_MTX_11 (209 * 16) + +2495004-2495046 SPI: COPI data: 7D : Set B2S Mount Matrix 11 to 0x40000000 +2495046-2495088 SPI: COPI data: 40 +2495088-2495130 SPI: COPI data: 00 +2495130-2495172 SPI: COPI data: 00 +2495172-2495214 SPI: COPI data: 00 + +2495260-2495304 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2495302-2495346 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2495393-2495437 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2495435-2495479 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2495723-2495767 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2495765-2495809 SPI: COPI data: 14 : B2S_MTX_12 (209 * 16 + 4) + +2495851-2495893 SPI: COPI data: 7D : Set B2S Mount Matrix 12 to 0x00000000 +2495893-2495935 SPI: COPI data: 00 +2495935-2495977 SPI: COPI data: 00 +2495977-2496019 SPI: COPI data: 00 +2496019-2496061 SPI: COPI data: 00 + +2496107-2496149 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2496149-2496191 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2496240-2496282 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2496282-2496324 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2496570-2496614 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2496612-2496656 SPI: COPI data: 18 : B2S_MTX_20 (209 * 16 + 8) + +2496698-2496740 SPI: COPI data: 7D : Set B2S Mount Matrix 20 to 0x00000000 +2496740-2496782 SPI: COPI data: 00 +2496782-2496824 SPI: COPI data: 00 +2496824-2496866 SPI: COPI data: 00 +2496866-2496908 SPI: COPI data: 00 + +2496954-2496996 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2496996-2497038 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2497087-2497129 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2497129-2497171 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2497417-2497461 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2497459-2497503 SPI: COPI data: 1C : B2S_MTX_21 (209 * 16 + 12) + +2497545-2497587 SPI: COPI data: 7D : Set B2S Mount Matrix 21 to 0x00000000 +2497587-2497629 SPI: COPI data: 00 +2497629-2497671 SPI: COPI data: 00 +2497671-2497713 SPI: COPI data: 00 +2497713-2497755 SPI: COPI data: 00 + +2497801-2497843 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2497843-2497885 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2497934-2497976 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2497976-2498018 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2498264-2498308 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2498306-2498350 SPI: COPI data: 20 : B2S_MTX_22 (210 * 16) + +2498392-2498434 SPI: COPI data: 7D : Set B2S Mount Matrix 22 to 0x40000000 +2498434-2498476 SPI: COPI data: 40 +2498476-2498518 SPI: COPI data: 00 +2498518-2498560 SPI: COPI data: 00 +2498560-2498602 SPI: COPI data: 00 + + + +2498648-2498690 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2498690-2498732 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2498917-2498959 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2498959-2499001 SPI: COPI data: 01 : Set PWR_MGMT_1 : Auto clock best available + +2499251-2499295 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2499293-2499337 SPI: COPI data: 00 : B2S_MTX_00 (208 * 16) + +2499379-2499421 SPI: COPI data: 7D : Set B2S Mount Matrix 00 to 0x40000000 +2499421-2499463 SPI: COPI data: 40 +2499463-2499505 SPI: COPI data: 00 +2499505-2499547 SPI: COPI data: 00 +2499547-2499589 SPI: COPI data: 00 + +2499635-2499677 SPI: COPI data: 06 +2499677-2499719 SPI: COPI data: 21 + +2499768-2499810 SPI: COPI data: 06 +2499810-2499852 SPI: COPI data: 01 + +2500098-2500140 SPI: COPI data: 7C +2500140-2500182 SPI: COPI data: 04 + +2500226-2500268 SPI: COPI data: 7D +2500268-2500310 SPI: COPI data: 00 +2500310-2500352 SPI: COPI data: 00 +2500352-2500394 SPI: COPI data: 00 +2500394-2500436 SPI: COPI data: 00 + +2500482-2500524 SPI: COPI data: 06 +2500524-2500566 SPI: COPI data: 21 + +2500615-2500657 SPI: COPI data: 06 +2500657-2500699 SPI: COPI data: 01 + +2500946-2500988 SPI: COPI data: 7C +2500988-2501030 SPI: COPI data: 08 + +2501073-2501117 SPI: COPI data: 7D +2501115-2501159 SPI: COPI data: 00 +2501157-2501201 SPI: COPI data: 00 +2501199-2501243 SPI: COPI data: 00 +2501241-2501285 SPI: COPI data: 00 + +2501330-2501372 SPI: COPI data: 06 +2501372-2501414 SPI: COPI data: 21 + +2501463-2501505 SPI: COPI data: 06 +2501505-2501547 SPI: COPI data: 01 + +2501793-2501835 SPI: COPI data: 7C +2501835-2501877 SPI: COPI data: 0C + +2501920-2501964 SPI: COPI data: 7D +2501962-2502006 SPI: COPI data: 00 +2502004-2502048 SPI: COPI data: 00 +2502046-2502090 SPI: COPI data: 00 +2502088-2502132 SPI: COPI data: 00 + +2502176-2502220 SPI: COPI data: 06 +2502218-2502262 SPI: COPI data: 21 + +2502309-2502353 SPI: COPI data: 06 +2502351-2502395 SPI: COPI data: 01 + +2502640-2502682 SPI: COPI data: 7C +2502682-2502724 SPI: COPI data: 10 + +2502767-2502811 SPI: COPI data: 7D +2502809-2502853 SPI: COPI data: 40 +2502851-2502895 SPI: COPI data: 00 +2502893-2502937 SPI: COPI data: 00 +2502935-2502979 SPI: COPI data: 00 + +2503023-2503065 SPI: COPI data: 06 +2503065-2503107 SPI: COPI data: 21 + +2503156-2503198 SPI: COPI data: 06 +2503198-2503240 SPI: COPI data: 01 + +2503487-2503529 SPI: COPI data: 7C +2503529-2503571 SPI: COPI data: 14 + +2503614-2503658 SPI: COPI data: 7D +2503656-2503700 SPI: COPI data: 00 +2503698-2503742 SPI: COPI data: 00 +2503740-2503784 SPI: COPI data: 00 +2503782-2503826 SPI: COPI data: 00 + +2503870-2503914 SPI: COPI data: 06 +2503912-2503956 SPI: COPI data: 21 + +2504003-2504047 SPI: COPI data: 06 +2504045-2504089 SPI: COPI data: 01 + +2504333-2504376 SPI: COPI data: 7C +2504376-2504418 SPI: COPI data: 18 + +2504461-2504505 SPI: COPI data: 7D +2504503-2504547 SPI: COPI data: 00 +2504545-2504589 SPI: COPI data: 00 +2504587-2504631 SPI: COPI data: 00 +2504629-2504673 SPI: COPI data: 00 + +2504717-2504759 SPI: COPI data: 06 +2504759-2504801 SPI: COPI data: 21 + +2504850-2504894 SPI: COPI data: 06 +2504892-2504936 SPI: COPI data: 01 + +2505181-2505223 SPI: COPI data: 7C +2505223-2505265 SPI: COPI data: 1C + +2505308-2505352 SPI: COPI data: 7D +2505350-2505394 SPI: COPI data: 00 +2505392-2505436 SPI: COPI data: 00 +2505434-2505478 SPI: COPI data: 00 +2505476-2505520 SPI: COPI data: 00 + +2505564-2505608 SPI: COPI data: 06 +2505606-2505650 SPI: COPI data: 21 + +2505697-2505741 SPI: COPI data: 06 +2505739-2505783 SPI: COPI data: 01 + +2506027-2506071 SPI: COPI data: 7C +2506069-2506113 SPI: COPI data: 20 + +2506155-2506197 SPI: COPI data: 7D +2506197-2506239 SPI: COPI data: 40 +2506239-2506281 SPI: COPI data: 00 +2506281-2506323 SPI: COPI data: 00 +2506323-2506365 SPI: COPI data: 00 + + + +2506411-2506453 SPI: COPI data: 06 +2506453-2506495 SPI: COPI data: 21 + +2506680-2506722 SPI: COPI data: 06 +2506722-2506764 SPI: COPI data: 01 + +2507011-2507053 SPI: COPI data: 7C +2507053-2507095 SPI: COPI data: 00 + +2507138-2507182 SPI: COPI data: 7D +2507180-2507224 SPI: COPI data: 40 +2507222-2507266 SPI: COPI data: 00 +2507264-2507308 SPI: COPI data: 00 +2507306-2507350 SPI: COPI data: 00 + +2507394-2507438 SPI: COPI data: 06 +2507436-2507479 SPI: COPI data: 21 + +2507528-2507570 SPI: COPI data: 06 +2507570-2507612 SPI: COPI data: 01 + +2507858-2507900 SPI: COPI data: 7C +2507900-2507942 SPI: COPI data: 04 + +2507985-2508029 SPI: COPI data: 7D +2508027-2508071 SPI: COPI data: 00 +2508069-2508113 SPI: COPI data: 00 +2508111-2508155 SPI: COPI data: 00 +2508153-2508197 SPI: COPI data: 00 + +2508241-2508285 SPI: COPI data: 06 +2508283-2508327 SPI: COPI data: 21 + +2508374-2508418 SPI: COPI data: 06 +2508416-2508460 SPI: COPI data: 01 + +2508705-2508747 SPI: COPI data: 7C +2508747-2508789 SPI: COPI data: 08 + +2508832-2508876 SPI: COPI data: 7D +2508874-2508918 SPI: COPI data: 00 +2508916-2508960 SPI: COPI data: 00 +2508958-2509002 SPI: COPI data: 00 +2509000-2509044 SPI: COPI data: 00 + +2509088-2509132 SPI: COPI data: 06 +2509130-2509174 SPI: COPI data: 21 + +2509222-2509264 SPI: COPI data: 06 +2509264-2509306 SPI: COPI data: 01 + +2509552-2509594 SPI: COPI data: 7C +2509594-2509636 SPI: COPI data: 0C + +2509680-2509722 SPI: COPI data: 7D +2509722-2509764 SPI: COPI data: 00 +2509764-2509806 SPI: COPI data: 00 +2509806-2509848 SPI: COPI data: 00 +2509848-2509890 SPI: COPI data: 00 + +2509935-2509979 SPI: COPI data: 06 +2509977-2510021 SPI: COPI data: 21 + +2510068-2510112 SPI: COPI data: 06 +2510110-2510154 SPI: COPI data: 01 + +2510399-2510441 SPI: COPI data: 7C +2510441-2510483 SPI: COPI data: 10 + +2510526-2510570 SPI: COPI data: 7D +2510568-2510612 SPI: COPI data: 40 +2510610-2510654 SPI: COPI data: 00 +2510652-2510696 SPI: COPI data: 00 +2510694-2510738 SPI: COPI data: 00 + +2510782-2510826 SPI: COPI data: 06 +2510824-2510868 SPI: COPI data: 21 + +2510915-2510957 SPI: COPI data: 06 +2510957-2510999 SPI: COPI data: 01 + +2511249-2511291 SPI: COPI data: 7C +2511291-2511333 SPI: COPI data: 14 + +2511377-2511419 SPI: COPI data: 7D +2511419-2511461 SPI: COPI data: 00 +2511461-2511503 SPI: COPI data: 00 +2511503-2511545 SPI: COPI data: 00 +2511545-2511587 SPI: COPI data: 00 + +2511633-2511675 SPI: COPI data: 06 +2511675-2511717 SPI: COPI data: 21 + +2511766-2511808 SPI: COPI data: 06 +2511808-2511850 SPI: COPI data: 01 + +2512096-2512138 SPI: COPI data: 7C +2512138-2512180 SPI: COPI data: 18 + +2512224-2512266 SPI: COPI data: 7D +2512266-2512308 SPI: COPI data: 00 +2512308-2512350 SPI: COPI data: 00 +2512350-2512392 SPI: COPI data: 00 +2512392-2512434 SPI: COPI data: 00 + +2512479-2512523 SPI: COPI data: 06 +2512521-2512565 SPI: COPI data: 21 + +2512613-2512655 SPI: COPI data: 06 +2512655-2512697 SPI: COPI data: 01 + +2512944-2512986 SPI: COPI data: 7C +2512986-2513028 SPI: COPI data: 1C + +2513071-2513115 SPI: COPI data: 7D +2513113-2513157 SPI: COPI data: 00 +2513155-2513199 SPI: COPI data: 00 +2513197-2513241 SPI: COPI data: 00 +2513239-2513283 SPI: COPI data: 00 + +2513327-2513371 SPI: COPI data: 06 +2513369-2513413 SPI: COPI data: 21 + +2513460-2513504 SPI: COPI data: 06 +2513502-2513546 SPI: COPI data: 01 + +2513791-2513833 SPI: COPI data: 7C +2513833-2513875 SPI: COPI data: 20 + +2513918-2513962 SPI: COPI data: 7D +2513960-2514004 SPI: COPI data: 40 +2514002-2514046 SPI: COPI data: 00 +2514044-2514088 SPI: COPI data: 00 +2514086-2514130 SPI: COPI data: 00 + + + +2514174-2514218 SPI: COPI data: 06 +2514216-2514260 SPI: COPI data: 21 + +2514443-2514485 SPI: COPI data: 06 +2514485-2514527 SPI: COPI data: 01 + +2514773-2514815 SPI: COPI data: 7C +2514815-2514857 SPI: COPI data: 00 + +2514901-2514943 SPI: COPI data: 7D +2514943-2514985 SPI: COPI data: 40 +2514985-2515027 SPI: COPI data: 00 +2515027-2515069 SPI: COPI data: 00 +2515069-2515111 SPI: COPI data: 00 + +2515156-2515200 SPI: COPI data: 06 +2515198-2515242 SPI: COPI data: 21 + +2515290-2515332 SPI: COPI data: 06 +2515332-2515374 SPI: COPI data: 01 + +2515620-2515662 SPI: COPI data: 7C +2515662-2515704 SPI: COPI data: 04 + +2515748-2515790 SPI: COPI data: 7D +2515790-2515832 SPI: COPI data: 00 +2515832-2515874 SPI: COPI data: 00 +2515874-2515916 SPI: COPI data: 00 +2515916-2515958 SPI: COPI data: 00 + +2516004-2516046 SPI: COPI data: 06 +2516046-2516088 SPI: COPI data: 21 + +2516137-2516179 SPI: COPI data: 06 +2516179-2516221 SPI: COPI data: 01 + +2516467-2516509 SPI: COPI data: 7C +2516509-2516551 SPI: COPI data: 08 + +2516594-2516638 SPI: COPI data: 7D +2516636-2516680 SPI: COPI data: 00 +2516678-2516722 SPI: COPI data: 00 +2516720-2516763 SPI: COPI data: 00 +2516763-2516805 SPI: COPI data: 00 + +2516851-2516893 SPI: COPI data: 06 +2516893-2516935 SPI: COPI data: 21 + +2516984-2517026 SPI: COPI data: 06 +2517026-2517068 SPI: COPI data: 01 + +2517318-2517360 SPI: COPI data: 7C +2517360-2517402 SPI: COPI data: 0C + +2517445-2517489 SPI: COPI data: 7D +2517487-2517531 SPI: COPI data: 00 +2517529-2517573 SPI: COPI data: 00 +2517571-2517615 SPI: COPI data: 00 +2517613-2517657 SPI: COPI data: 00 + +2517701-2517743 SPI: COPI data: 06 +2517743-2517787 SPI: COPI data: 21 + +2517834-2517878 SPI: COPI data: 06 +2517876-2517920 SPI: COPI data: 01 + +2518164-2518208 SPI: COPI data: 7C +2518206-2518250 SPI: COPI data: 10 + +2518292-2518334 SPI: COPI data: 7D +2518334-2518376 SPI: COPI data: 40 +2518376-2518418 SPI: COPI data: 00 +2518418-2518460 SPI: COPI data: 00 +2518460-2518502 SPI: COPI data: 00 + +2518548-2518590 SPI: COPI data: 06 +2518590-2518632 SPI: COPI data: 21 + +2518681-2518723 SPI: COPI data: 06 +2518723-2518765 SPI: COPI data: 01 + +2519012-2519054 SPI: COPI data: 7C +2519054-2519096 SPI: COPI data: 14 + +2519140-2519182 SPI: COPI data: 7D +2519182-2519224 SPI: COPI data: 00 +2519224-2519266 SPI: COPI data: 00 +2519266-2519308 SPI: COPI data: 00 +2519308-2519350 SPI: COPI data: 00 + +2519396-2519438 SPI: COPI data: 06 +2519438-2519480 SPI: COPI data: 21 + +2519529-2519571 SPI: COPI data: 06 +2519571-2519613 SPI: COPI data: 01 + +2519859-2519903 SPI: COPI data: 7C +2519901-2519945 SPI: COPI data: 18 + +2519987-2520029 SPI: COPI data: 7D +2520029-2520071 SPI: COPI data: 00 +2520071-2520113 SPI: COPI data: 00 +2520113-2520155 SPI: COPI data: 00 +2520155-2520197 SPI: COPI data: 00 + +2520243-2520285 SPI: COPI data: 06 +2520285-2520327 SPI: COPI data: 21 + +2520376-2520418 SPI: COPI data: 06 +2520418-2520460 SPI: COPI data: 01 + +2520706-2520748 SPI: COPI data: 7C +2520748-2520790 SPI: COPI data: 1C + +2520834-2520876 SPI: COPI data: 7D +2520876-2520918 SPI: COPI data: 00 +2520918-2520960 SPI: COPI data: 00 +2520960-2521002 SPI: COPI data: 00 +2521002-2521044 SPI: COPI data: 00 + +2521090-2521132 SPI: COPI data: 06 +2521132-2521174 SPI: COPI data: 21 + +2521223-2521265 SPI: COPI data: 06 +2521265-2521307 SPI: COPI data: 01 + +2521553-2521597 SPI: COPI data: 7C +2521595-2521639 SPI: COPI data: 20 + +2521681-2521723 SPI: COPI data: 7D +2521723-2521765 SPI: COPI data: 40 +2521765-2521807 SPI: COPI data: 00 +2521807-2521849 SPI: COPI data: 00 +2521849-2521891 SPI: COPI data: 00 + + + +2521937-2521979 SPI: COPI data: 06 +2521979-2522021 SPI: COPI data: 21 + +2522340-2522382 SPI: COPI data: 06 +2522382-2522424 SPI: COPI data: 01 + +2522670-2522712 SPI: COPI data: 7C +2522712-2522754 SPI: COPI data: 00 + +2522798-2522840 SPI: COPI data: 7D +2522840-2522882 SPI: COPI data: 40 +2522882-2522924 SPI: COPI data: 00 +2522924-2522966 SPI: COPI data: 00 +2522966-2523008 SPI: COPI data: 00 + +2523054-2523096 SPI: COPI data: 06 +2523096-2523138 SPI: COPI data: 21 + +2523187-2523229 SPI: COPI data: 06 +2523229-2523271 SPI: COPI data: 01 + +2523517-2523559 SPI: COPI data: 7C +2523559-2523601 SPI: COPI data: 04 + +2523645-2523687 SPI: COPI data: 7D +2523687-2523729 SPI: COPI data: 00 +2523729-2523771 SPI: COPI data: 00 +2523771-2523813 SPI: COPI data: 00 +2523813-2523855 SPI: COPI data: 00 + +2523900-2523944 SPI: COPI data: 06 +2523942-2523985 SPI: COPI data: 21 + +2524034-2524076 SPI: COPI data: 06 +2524076-2524118 SPI: COPI data: 01 + +2524364-2524406 SPI: COPI data: 7C +2524406-2524448 SPI: COPI data: 08 + +2524491-2524535 SPI: COPI data: 7D +2524533-2524577 SPI: COPI data: 00 +2524575-2524619 SPI: COPI data: 00 +2524617-2524661 SPI: COPI data: 00 +2524659-2524703 SPI: COPI data: 00 + +2524747-2524791 SPI: COPI data: 06 +2524789-2524833 SPI: COPI data: 21 + +2524880-2524922 SPI: COPI data: 06 +2524922-2524964 SPI: COPI data: 01 + +2525214-2525256 SPI: COPI data: 7C +2525256-2525298 SPI: COPI data: 0C + +2525342-2525384 SPI: COPI data: 7D +2525384-2525426 SPI: COPI data: 00 +2525426-2525468 SPI: COPI data: 00 +2525468-2525510 SPI: COPI data: 00 +2525510-2525552 SPI: COPI data: 00 + +2525598-2525640 SPI: COPI data: 06 +2525640-2525682 SPI: COPI data: 21 + +2525731-2525773 SPI: COPI data: 06 +2525773-2525815 SPI: COPI data: 01 + +2526061-2526103 SPI: COPI data: 7C +2526103-2526145 SPI: COPI data: 10 + +2526189-2526231 SPI: COPI data: 7D +2526231-2526273 SPI: COPI data: 40 +2526273-2526315 SPI: COPI data: 00 +2526315-2526357 SPI: COPI data: 00 +2526357-2526399 SPI: COPI data: 00 + +2526444-2526488 SPI: COPI data: 06 +2526444-2526488 SPI: CIPO data: 00 +2526486-2526530 SPI: COPI data: 21 +2526486-2526530 SPI: CIPO data: 00 + +2526577-2526621 SPI: COPI data: 06 +2526577-2526621 SPI: CIPO data: 00 +2526619-2526663 SPI: COPI data: 01 +2526619-2526663 SPI: CIPO data: 00 + +2526908-2526952 SPI: COPI data: 7C +2526950-2526994 SPI: COPI data: 14 + +2527036-2527080 SPI: COPI data: 7D +2527078-2527122 SPI: COPI data: 00 +2527120-2527164 SPI: COPI data: 00 +2527164-2527206 SPI: COPI data: 00 +2527206-2527248 SPI: COPI data: 00 + +2527294-2527336 SPI: COPI data: 06 +2527336-2527378 SPI: COPI data: 21 + +2527427-2527469 SPI: COPI data: 06 +2527469-2527511 SPI: COPI data: 01 + +2527757-2527799 SPI: COPI data: 7C +2527799-2527841 SPI: COPI data: 18 + +2527885-2527927 SPI: COPI data: 7D +2527927-2527969 SPI: COPI data: 00 +2527969-2528011 SPI: COPI data: 00 +2528011-2528053 SPI: COPI data: 00 +2528053-2528095 SPI: COPI data: 00 + +2528141-2528183 SPI: COPI data: 06 +2528183-2528225 SPI: COPI data: 21 + +2528274-2528316 SPI: COPI data: 06 +2528316-2528358 SPI: COPI data: 01 + +2528604-2528646 SPI: COPI data: 7C +2528646-2528688 SPI: COPI data: 1C + +2528732-2528774 SPI: COPI data: 7D +2528774-2528816 SPI: COPI data: 00 +2528816-2528858 SPI: COPI data: 00 +2528858-2528900 SPI: COPI data: 00 +2528900-2528942 SPI: COPI data: 00 + +2528987-2529031 SPI: COPI data: 06 +2529029-2529073 SPI: COPI data: 21 + +2529120-2529164 SPI: COPI data: 06 +2529164-2529206 SPI: COPI data: 01 + +2529453-2529495 SPI: COPI data: 7C +2529495-2529537 SPI: COPI data: 20 + +2529580-2529624 SPI: COPI data: 7D +2529622-2529666 SPI: COPI data: 40 +2529664-2529708 SPI: COPI data: 00 +2529706-2529750 SPI: COPI data: 00 +2529748-2529792 SPI: COPI data: 00 + +2529836-2529878 SPI: COPI data: 06 +2529878-2529920 SPI: COPI data: 21 + + + +2531860-2531902 SPI: COPI data: 06 +2531902-2531944 SPI: COPI data: 01 + +2532190-2532232 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2532232-2532274 SPI: COPI data: 00 : Bank 0 is selected + +2532317-2532361 SPI: COPI data: 7F : Write Bank 3 Reg 0x7F REG_BANK_SEL +2532359-2532403 SPI: COPI data: 20 : Select Bank 2 + +2532446-2532488 SPI: COPI data: 94 : Read Bank 2 Reg 0x14 ACCEL_CONFIG +2532488-2532530 SPI: CIPO data: 01 : Accel DLPF is enabled; +/-2g; 246Hz (3dB); 1125Hz + +2532578-2532620 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2532620-2532662 SPI: CIPO data: 20 : Bank 2 is selected + +2532706-2532748 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2532748-2532790 SPI: COPI data: 00 : Select Bank 0 + +2532834-2532876 SPI: COPI data: 06 +2532876-2532918 SPI: COPI data: 21 + +2532967-2533009 SPI: COPI data: 06 +2533009-2533051 SPI: COPI data: 01 + + + +2533301-2533343 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2533343-2533385 SPI: CIPO data: 00 : Bank 0 is selected + +2533428-2533472 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2533470-2533514 SPI: COPI data: 20 : Select Bank 2 + +2533556-2533598 SPI: COPI data: 14 : Write Bank 2 Reg 0x14 ACCEL_CONFIG +2533598-2533640 SPI: COPI data: 02 : ACCEL_FCHOICE 0 (Bypass Accel DLPF); +/- 4g; 4500Hz + +2533687-2533729 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2533729-2533771 SPI: CIPO data: 20 : Bank 2 is selected + +2533814-2533858 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2533856-2533900 SPI: COPI data: 00 : Select Bank 0 + +2533942-2533986 SPI: COPI data: 06 +2533984-2534028 SPI: COPI data: 21 + +2534075-2534119 SPI: COPI data: 06 +2534117-2534161 SPI: COPI data: 01 + +2534405-2534449 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2534447-2534491 SPI: CIPO data: 00 : Bank 0 is selected + +2534533-2534575 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2534575-2534617 SPI: COPI data: 20 : Select Bank 2 + +2534662-2534704 SPI: COPI data: 95 : Read Bank 2 Reg 0x15 ACCEL_CONFIG_2 +2534704-2534746 SPI: CIPO data: 00 : DEC3_CFG: 0 (Averages: 1) + +2534794-2534836 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2534836-2534878 SPI: CIPO data: 20 : Bank 2 is selected + +2534921-2534965 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2534963-2535007 SPI: COPI data: 00 : Select Bank 0 + +2535049-2535091 SPI: COPI data: 06 +2535091-2535133 SPI: COPI data: 21 + +2535182-2535226 SPI: COPI data: 06 +2535224-2535268 SPI: COPI data: 01 + +2535512-2535556 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2535554-2535598 SPI: CIPO data: 00 : Bank 0 is selected + +2535640-2535682 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2535682-2535724 SPI: COPI data: 20 : Select Bank 2 + +2535768-2535810 SPI: COPI data: 15 : Write Bank 2 Reg 0x15 ACCEL_CONFIG_2 +2535810-2535852 SPI: COPI data: 00 : DEC3_CFG: 0 (Averages: 1) + +2535899-2535941 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2535941-2535983 SPI: CIPO data: 20 : Bank 2 is selected + +2536026-2536070 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2536068-2536112 SPI: COPI data: 00 : Select Bank 0 + +2536154-2536196 SPI: COPI data: 06 +2536196-2536238 SPI: COPI data: 21 + +2536288-2536332 SPI: COPI data: 06 +2536331-2536373 SPI: COPI data: 01 + +2536618-2536662 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2536660-2536704 SPI: COPI data: 01 : Bank 0x01 + +2536746-2536790 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2536788-2536832 SPI: COPI data: E0 : ACC_SCALE (30 * 16) + +2536874-2536916 SPI: COPI data: 7D : Set ACC_SCALE to 0x04000000 +2536916-2536958 SPI: COPI data: 04 +2536958-2537000 SPI: COPI data: 00 +2537000-2537042 SPI: COPI data: 00 +2537042-2537084 SPI: COPI data: 00 + +2537130-2537172 SPI: COPI data: 06 +2537172-2537214 SPI: COPI data: 21 + +2537264-2537308 SPI: COPI data: 06 +2537306-2537350 SPI: COPI data: 01 + +2537594-2537638 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2537636-2537680 SPI: COPI data: 04 : Bank 0x04 + +2537722-2537766 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2537764-2537808 SPI: COPI data: F4 : ACC_SCALE2 (79 * 16 + 4) + +2537850-2537892 SPI: COPI data: 7D : Set ACC_SCALE2 to 0x00040000 +2537892-2537934 SPI: COPI data: 00 +2537934-2537976 SPI: COPI data: 04 +2537976-2538018 SPI: COPI data: 00 +2538018-2538060 SPI: COPI data: 00 + +2538106-2538148 SPI: COPI data: 06 +2538148-2538190 SPI: COPI data: 21 + +2538241-2538285 SPI: COPI data: 06 +2538283-2538327 SPI: COPI data: 01 + +2538571-2538615 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2538613-2538657 SPI: CIPO data: 00 : Bank 0 is selected + +2538699-2538741 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2538741-2538783 SPI: COPI data: 20 : Select Bank 2 + +2538828-2538872 SPI: COPI data: 94 : Read Bank 2 Reg 0x14 ACCEL_CONFIG +2538870-2538914 SPI: CIPO data: 02 : ACCEL_FCHOICE 0 (Bypass Accel DLPF); +/- 4g; 4500Hz + +2538960-2539004 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2539002-2539046 SPI: CIPO data: 20 : Bank 2 is selected + +2539088-2539130 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2539130-2539172 SPI: COPI data: 00 : Select Bank 0 + +2539216-2539258 SPI: COPI data: 06 +2539258-2539300 SPI: COPI data: 21 + +2539349-2539393 SPI: COPI data: 06 +2539391-2539435 SPI: COPI data: 01 + +2539679-2539723 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2539721-2539765 SPI: CIPO data: 00 : Bank 0 is selected + +2539807-2539849 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2539849-2539891 SPI: COPI data: 20 : Select Bank 2 + +2539935-2539977 SPI: COPI data: 14 : Write Bank 2 Reg 0x14 ACCEL_CONFIG +2539977-2540019 SPI: COPI data: 02 : ACCEL_FCHOICE 0 (Bypass Accel DLPF); +/- 4g; 4500Hz + +2540066-2540108 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2540108-2540150 SPI: CIPO data: 20 : Bank 2 is selected + +2540193-2540237 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2540235-2540279 SPI: COPI data: 00 : Select Bank 0 + +2540321-2540363 SPI: COPI data: 06 +2540363-2540405 SPI: COPI data: 21 + +2540454-2540498 SPI: COPI data: 06 +2540496-2540540 SPI: COPI data: 01 + +2540784-2540828 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2540826-2540870 SPI: CIPO data: 00 : Bank 0 is selected + +2540912-2540954 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2540954-2540996 SPI: COPI data: 20 : Select Bank 2 + +2541040-2541084 SPI: COPI data: 95 : Read Bank 2 Reg 0x15 ACCEL_CONFIG_2 +2541082-2541126 SPI: CIPO data: 00 : DEC3_CFG: 0 (Averages: 1) + +2541172-2541216 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2541214-2541258 SPI: CIPO data: 20 : Bank 2 is selected + +2541300-2541342 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2541342-2541384 SPI: CIPO data: 00 : Select Bank 0 + +2541428-2541470 SPI: COPI data: 06 +2541470-2541512 SPI: COPI data: 21 + +2541561-2541605 SPI: COPI data: 06 +2541603-2541647 SPI: COPI data: 01 + +2541891-2541933 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2541933-2541975 SPI: CIPO data: 00 : Bank 0 is selected + +2542019-2542061 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2542061-2542103 SPI: COPI data: 20 : Select Bank 2 + +2542147-2542189 SPI: COPI data: 15 : Write Bank 2 Reg 0x15 ACCEL_CONFIG_2 +2542189-2542231 SPI: COPI data: 00 : DEC3_CFG: 0 (Averages: 1) + +2542277-2542321 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2542319-2542363 SPI: CIPO data: 20 : Bank 2 is selected + +2542405-2542447 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2542447-2542489 SPI: CIPO data: 00 : Select Bank 0 + +2542533-2542575 SPI: COPI data: 06 +2542575-2542617 SPI: COPI data: 21 + +2542667-2542711 SPI: COPI data: 06 +2542709-2542753 SPI: COPI data: 01 + +2542998-2543040 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2543040-2543082 SPI: COPI data: 01 : Bank 0x01 + +2543126-2543168 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2543168-2543210 SPI: COPI data: E0 : ACC_SCALE (30 * 16) + +2543254-2543296 SPI: COPI data: 7D : Set ACC_SCALE to 0x04000000 +2543296-2543338 SPI: COPI data: 04 +2543338-2543380 SPI: COPI data: 00 +2543380-2543422 SPI: COPI data: 00 +2543422-2543464 SPI: COPI data: 00 + +2543510-2543552 SPI: COPI data: 06 +2543552-2543594 SPI: COPI data: 21 + +2543644-2543688 SPI: COPI data: 06 +2543686-2543730 SPI: COPI data: 01 + +2543974-2544016 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2544016-2544058 SPI: COPI data: 04 : Bank 0x04 + +2544102-2544144 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2544144-2544186 SPI: COPI data: F4 : ACC_SCALE2 (79 * 16 + 4) + +2544230-2544272 SPI: COPI data: 7D : Set ACC_SCALE2 to 0x00040000 +2544272-2544314 SPI: COPI data: 00 +2544314-2544356 SPI: COPI data: 04 +2544356-2544398 SPI: COPI data: 00 +2544398-2544440 SPI: COPI data: 00 + +2544486-2544528 SPI: COPI data: 06 +2544528-2544570 SPI: COPI data: 21 + +2544621-2544665 SPI: COPI data: 06 +2544663-2544707 SPI: COPI data: 01 + +2544952-2544994 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2544994-2545036 SPI: CIPO data: 00 : Bank 0 is selected + +2545080-2545122 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2545122-2545164 SPI: COPI data: 20 : Select Bank 2 + +2545212-2545254 SPI: COPI data: 81 : Read Bank 2 Reg 0x01 GYRO_CONFIG_1 +2545254-2545296 SPI: CIPO data: 01 : Enable gyro DLPF; +/-250dps; 9000 Hz (i.e. the reset value) + +2545344-2545386 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2545386-2545428 SPI: CIPO data: 20 : Bank 2 is selected + +2545472-2545514 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2545514-2545556 SPI: COPI data: 00 : Select Bank 0 + +2545600-2545642 SPI: COPI data: 06 +2545642-2545684 SPI: COPI data: 21 + +2545733-2545777 SPI: COPI data: 06 +2545775-2545819 SPI: COPI data: 01 + +2546063-2546105 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2546105-2546147 SPI: CIPO data: 00 : Bank 0 is selected + +2546191-2546233 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2546233-2546275 SPI: COPI data: 20 : Select Bank 2 + +2546319-2546363 SPI: COPI data: 01 : Write Bank 2 Reg 0x01 GYRO_CONFIG_1 +2546361-2546405 SPI: COPI data: 07 : Enable gyro DLPF; +/- 2000dps + +2546450-2546494 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2546492-2546536 SPI: CIPO data: 20 : Bank 2 is selected + +2546578-2546620 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2546620-2546662 SPI: COPI data: 00 : Select Bank 0 + +2546706-2546748 SPI: COPI data: 06 +2546748-2546790 SPI: COPI data: 21 + +2546839-2546883 SPI: COPI data: 06 +2546881-2546925 SPI: COPI data: 01 + +2547169-2547211 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2547211-2547253 SPI: CIPO data: 00 : Bank 0 is selected + +2547297-2547339 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2547339-2547381 SPI: COPI data: 20 : Select Bank 2 + +2547425-2547469 SPI: COPI data: 82 : Read Bank 2 Reg 0x02 GYRO_CONFIG_2 +2547467-2547511 SPI: CIPO data: 00 : 1x averaging (i.e. reset value) + +2547557-2547601 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2547599-2547643 SPI: CIPO data: 20 : Bank 2 is selected + +2547685-2547729 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2547727-2547771 SPI: COPI data: 00 : Select Bank 0 + +2547813-2547855 SPI: COPI data: 06 +2547855-2547897 SPI: COPI data: 21 + +2547947-2547989 SPI: COPI data: 06 +2547989-2548031 SPI: COPI data: 01 + +2548277-2548319 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2548319-2548361 SPI: CIPO data: 00 : Bank 0 is selected + +2548405-2548447 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2548447-2548489 SPI: COPI data: 20 : Select Bank 2 + +2548532-2548576 SPI: COPI data: 02 : Write Bank 2 Reg 0x02 GYRO_CONFIG_2 +2548574-2548618 SPI: COPI data: 00 : 1x Averaging + +2548663-2548705 SPI: COPI data: FF : Read Bank 2 Reg 0x7F REG_BANK_SEL +2548705-2548749 SPI: CIPO data: 20 : Bank 2 is selected + +2548791-2548833 SPI: COPI data: 7F : Write Bank 2 Reg 0x7F REG_BANK_SEL +2548833-2548875 SPI: COPI data: 00 : Select Bank 0 + +2548919-2548961 SPI: COPI data: 06 +2548961-2549003 SPI: COPI data: 21 + +2549053-2549095 SPI: COPI data: 06 +2549095-2549137 SPI: COPI data: 01 + +2549386-2549430 SPI: COPI data: FF : Read Bank 0 Reg 0x7F REG_BANK_SEL +2549428-2549472 SPI: CIPO data: 00 : Bank 0 is selected + +2549514-2549556 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2549556-2549598 SPI: COPI data: 10 : Select Bank 1 + +2549643-2549685 SPI: COPI data: A8 : Read Bank 1 Reg 0x28 TIMEBASE_CORRECTION_PLL +2549685-2549727 SPI: CIPO data: 09 : +9% ? (or maybe +9/127 %) + +2549775-2549817 SPI: COPI data: FF : Read Bank 1 Reg 0x7F REG_BANK_SEL +2549817-2549859 SPI: CIPO data: 10 : Bank 1 is selected + +2549902-2549946 SPI: COPI data: 7F : Write Bank 1 Reg 0x7F REG_BANK_SEL +2549944-2549988 SPI: COPI data: 00 : Select Bank 0 + +2550030-2550074 SPI: COPI data: 06 +2550072-2550116 SPI: COPI data: 21 + +2550174-2550216 SPI: COPI data: 06 +2550216-2550258 SPI: COPI data: 01 + +2550504-2550546 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2550546-2550588 SPI: COPI data: 01 : Bank 0x01 + +2550632-2550674 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2550674-2550716 SPI: COPI data: 30 : GYRO_SF (19 * 16) + +2550760-2550802 SPI: COPI data: 7D : Set GYRO_SF to 0x276FBC37 +2550802-2550844 SPI: COPI data: 27 +2550844-2550886 SPI: COPI data: 6F +2550886-2550928 SPI: COPI data: BC +2550928-2550970 SPI: COPI data: 37 + +2551015-2551059 SPI: COPI data: 06 +2551057-2551101 SPI: COPI data: 21 + +2551150-2551194 SPI: COPI data: 06 +2551192-2551236 SPI: COPI data: 01 + +2551480-2551524 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2551522-2551566 SPI: COPI data: 04 : Bank 0x04 + +2551608-2551652 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2551650-2551694 SPI: COPI data: 8C : GYRO_FULLSCALE (72 * 16 + 12) + +2551736-2551778 SPI: COPI data: 7D : Set GYRO_FULLSCALE to 0x10000000 +2551778-2551822 SPI: COPI data: 10 +2551820-2551864 SPI: COPI data: 00 +2551862-2551906 SPI: COPI data: 00 +2551904-2551948 SPI: COPI data: 00 + +2551992-2552034 SPI: COPI data: 06 +2552034-2552076 SPI: COPI data: 21 + +2552128-2552170 SPI: COPI data: 06 +2552170-2552212 SPI: COPI data: 01 + +2552458-2552500 SPI: COPI data: FF +2552500-2552542 SPI: CIPO data: 00 + +2552585-2552629 SPI: COPI data: 7F : Write Bank 0 Reg 0x7F REG_BANK_SEL +2552627-2552671 SPI: COPI data: 20 : Select Bank 2 + +2552714-2552756 SPI: COPI data: 81 : Read Bank 2 Reg 0x01 GYRO_CONFIG_1 +2552756-2552798 SPI: CIPO data: 07 : Enable gyro DLPF; +/- 2000dps + +2552846-2552890 SPI: COPI data: FF +2552888-2552932 SPI: CIPO data: 20 + +2552974-2553016 SPI: COPI data: 7F +2553016-2553058 SPI: COPI data: 00 + +2553102-2553144 SPI: COPI data: 06 +2553144-2553186 SPI: COPI data: 21 + +2553236-2553278 SPI: COPI data: 06 +2553278-2553320 SPI: COPI data: 01 + +2553566-2553608 SPI: COPI data: FF +2553608-2553650 SPI: CIPO data: 00 + +2553693-2553737 SPI: COPI data: 7F +2553735-2553779 SPI: COPI data: 20 + +2553822-2553864 SPI: COPI data: 01 : Write Bank 2 Reg 0x01 GYRO_CONFIG_1 +2553864-2553906 SPI: COPI data: 07 : Enable gyro DLPF; +/- 2000dps; 196.6Hz (3dB) + +2553953-2553995 SPI: COPI data: FF +2553995-2554037 SPI: CIPO data: 20 + +2554081-2554123 SPI: COPI data: 7F +2554123-2554165 SPI: COPI data: 00 + +2554208-2554252 SPI: COPI data: 06 +2554250-2554294 SPI: COPI data: 21 + +2554342-2554384 SPI: COPI data: 06 +2554384-2554426 SPI: COPI data: 01 + +2554671-2554715 SPI: COPI data: FF +2554713-2554757 SPI: CIPO data: 00 + +2554799-2554841 SPI: COPI data: 7F +2554841-2554883 SPI: COPI data: 20 + +2554928-2554970 SPI: COPI data: 82 : Read Bank 2 Reg 0x02 GYRO_CONFIG_2 +2554970-2555012 SPI: CIPO data: 00 : 1x averaging + +2555060-2555102 SPI: COPI data: FF +2555102-2555144 SPI: CIPO data: 20 + +2555188-2555230 SPI: COPI data: 7F +2555230-2555272 SPI: COPI data: 00 + +2555316-2555358 SPI: COPI data: 06 +2555358-2555400 SPI: COPI data: 21 + +2555450-2555492 SPI: COPI data: 06 +2555492-2555534 SPI: COPI data: 01 + +2555779-2555823 SPI: COPI data: FF +2555821-2555865 SPI: CIPO data: 00 + +2555907-2555951 SPI: COPI data: 7F +2555949-2555993 SPI: COPI data: 20 + +2556035-2556077 SPI: COPI data: 02 : Write Bank 2 Reg 0x02 GYRO_CONFIG_2 +2556077-2556119 SPI: COPI data: 00 : 1x averaging + +2556166-2556208 SPI: COPI data: FF +2556208-2556250 SPI: CIPO data: 20 + +2556293-2556337 SPI: COPI data: 7F +2556335-2556379 SPI: COPI data: 00 + +2556421-2556465 SPI: COPI data: 06 +2556463-2556507 SPI: COPI data: 21 + +2556567-2556609 SPI: COPI data: 06 +2556609-2556651 SPI: COPI data: 01 + +2556898-2556940 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2556940-2556982 SPI: COPI data: 8C : GYRO_FULLSCALE (72 * 16 + 12) + +2557026-2557068 SPI: COPI data: 7D : Set GYRO_FULLSCALE to 0x10000000 +2557068-2557110 SPI: COPI data: 10 +2557110-2557152 SPI: COPI data: 00 +2557152-2557194 SPI: COPI data: 00 +2557194-2557236 SPI: COPI data: 00 + +2557282-2557324 SPI: COPI data: 06 +2557324-2557366 SPI: COPI data: 21 + +2557417-2557461 SPI: COPI data: 06 +2557459-2557503 SPI: COPI data: 01 + +2557747-2557791 SPI: COPI data: FF +2557789-2557833 SPI: CIPO data: 00 + +2557875-2557917 SPI: COPI data: 7F +2557917-2557959 SPI: COPI data: 20 + +2558004-2558046 SPI: COPI data: 81 : Read Bank 2 Reg 0x01 GYRO_CONFIG_1 +2558046-2558088 SPI: CIPO data: 07 : Enable gyro DLPF; +/- 2000dps; 196.6Hz (3dB) + +2558136-2558178 SPI: COPI data: FF +2558178-2558220 SPI: CIPO data: 20 + +2558263-2558307 SPI: COPI data: 7F +2558305-2558349 SPI: COPI data: 00 + +2558391-2558435 SPI: COPI data: 06 +2558433-2558477 SPI: COPI data: 21 + +2558525-2558567 SPI: COPI data: 06 +2558567-2558609 SPI: COPI data: 01 + +2558855-2558897 SPI: COPI data: FF +2558897-2558939 SPI: CIPO data: 00 + +2558982-2559026 SPI: COPI data: 7F +2559024-2559067 SPI: COPI data: 20 + +2559111-2559153 SPI: COPI data: 01 : Write Bank 2 Reg 0x01 GYRO_CONFIG_1 +2559153-2559195 SPI: COPI data: 07 : Enable gyro DLPF; +/- 2000dps; 196.6Hz (3dB) + +2559242-2559286 SPI: COPI data: FF +2559284-2559328 SPI: CIPO data: 20 + +2559370-2559412 SPI: COPI data: 7F +2559412-2559454 SPI: COPI data: 00 + +2559498-2559540 SPI: COPI data: 06 +2559540-2559582 SPI: COPI data: 21 + +2559631-2559673 SPI: COPI data: 06 +2559673-2559715 SPI: COPI data: 01 + +2559961-2560003 SPI: COPI data: FF +2560003-2560045 SPI: CIPO data: 00 + +2560089-2560131 SPI: COPI data: 7F +2560131-2560173 SPI: COPI data: 20 + +2560217-2560261 SPI: COPI data: 82 : Read Bank 2 Reg 0x02 GYRO_CONFIG_2 +2560259-2560303 SPI: CIPO data: 00 : 1x averaging + +2560349-2560393 SPI: COPI data: FF +2560391-2560435 SPI: CIPO data: 20 + +2560477-2560519 SPI: COPI data: 7F +2560519-2560561 SPI: COPI data: 00 + +2560605-2560647 SPI: COPI data: 06 +2560647-2560689 SPI: COPI data: 21 + +2560739-2560781 SPI: COPI data: 06 +2560781-2560823 SPI: COPI data: 01 + +2561070-2561112 SPI: COPI data: FF +2561112-2561154 SPI: CIPO data: 00 + +2561198-2561240 SPI: COPI data: 7F +2561240-2561282 SPI: COPI data: 20 + +2561325-2561369 SPI: COPI data: 02 : Write Bank 2 Reg 0x02 GYRO_CONFIG_2 +2561367-2561411 SPI: COPI data: 00 : 1x averaging + +2561456-2561498 SPI: COPI data: FF +2561498-2561540 SPI: CIPO data: 20 + +2561584-2561626 SPI: COPI data: 7F +2561626-2561668 SPI: COPI data: 00 + +2561712-2561754 SPI: COPI data: 06 +2561754-2561796 SPI: COPI data: 21 + +2561857-2561899 SPI: COPI data: 06 +2561899-2561941 SPI: COPI data: 01 + +2562187-2562231 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2562229-2562273 SPI: COPI data: 8C : GYRO_FULLSCALE (72 * 16 + 12) + +2562315-2562357 SPI: COPI data: 7D : Set GYRO_FULLSCALE to 0x10000000 +2562357-2562399 SPI: COPI data: 10 +2562399-2562441 SPI: COPI data: 00 +2562441-2562483 SPI: COPI data: 00 +2562483-2562525 SPI: COPI data: 00 + +2562571-2562613 SPI: COPI data: 06 +2562613-2562655 SPI: COPI data: 21 + +2562803-2562845 SPI: COPI data: FF +2562845-2562887 SPI: CIPO data: 00 + +2562931-2562973 SPI: COPI data: 7F +2562973-2563015 SPI: COPI data: 00 + +2563059-2563101 SPI: COPI data: 05 : Write Bank 0 Reg 0x05 LP_CONFIG +2563101-2563143 SPI: COPI data: 40 : Operate _only_ I2C master in duty cycled mode. ODR is determined by I2C_MST_ODR_CONFIG register. + +2563414-2563458 SPI: COPI data: 06 +2563456-2563500 SPI: COPI data: 01 + +2563744-2563786 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2563786-2563828 SPI: COPI data: 10 : Reset I2C peripheral module and put the serial interface in SPI mode only + +2563877-2563919 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2563919-2563961 SPI: COPI data: 47 : Disable pressure sensor and all gyro axes + +2564010-2564052 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2564052-2564094 SPI: COPI data: D0 : DMP Enable; FIFO Enable; Reset I2C peripheral module and put the serial interface in SPI mode only + +2564154-2564198 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2564196-2564240 SPI: COPI data: 00 : Bank 0x00 + +2564282-2564326 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2564324-2564368 SPI: COPI data: 40 : DATA_OUT_CTL1 (4 * 16) + +2564410-2564452 SPI: COPI data: 7D : Set DATA_OUT_CTL1 to 0x0000 +2564452-2564494 SPI: COPI data: 00 +2564494-2564536 SPI: COPI data: 00 + +2564587-2564629 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2564629-2564671 SPI: COPI data: 4C : DATA_INTR_CTL (4 * 16 + 12) + +2564714-2564758 SPI: COPI data: 7D : Set DATA_INTR_CTL to 0x0000 +2564756-2564800 SPI: COPI data: 00 +2564798-2564842 SPI: COPI data: 00 + +2564893-2564935 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2564935-2564977 SPI: COPI data: 42 : DATA_OUT_CTL2 (4 * 16 + 2) + +2565020-2565064 SPI: COPI data: 7D : Set DATA_OUT_CTL2 to 0x0000 +2565062-2565106 SPI: COPI data: 00 +2565104-2565148 SPI: COPI data: 00 + +2565199-2565243 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2565241-2565285 SPI: COPI data: 4E : MOTION_EVENT_CTL (4 * 16 + 14) + +2565327-2565369 SPI: COPI data: 7D : Set MOTION_EVENT_CTL to 0x0000 +2565369-2565411 SPI: COPI data: 00 +2565411-2565453 SPI: COPI data: 00 + +2565549-2565593 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2565591-2565635 SPI: COPI data: 7F : Disable pressure; all accel axes; all gyro axes + +2565681-2565723 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2565723-2565765 SPI: COPI data: 41 : Sleep; Auto clock + +2566015-2566057 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2566057-2566099 SPI: COPI data: 01 : Auto clock + +2566346-2566388 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2566388-2566430 SPI: COPI data: 7F : Disable pressure; all accel axes; all gyro axes + +2566481-2566523 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2566523-2566565 SPI: COPI data: 8A : DATA_RDY_STATUS (8 * 16 + 10) + +2566609-2566651 SPI: COPI data: 7D : Set DATA_RDY_STATUS to 0x0000 +2566651-2566693 SPI: COPI data: 00 +2566693-2566735 SPI: COPI data: 00 + +2566783-2566825 SPI: COPI data: 06 +2566825-2566867 SPI: COPI data: 21 + +2566921-2566963 SPI: COPI data: 06 +2566963-2567005 SPI: COPI data: 01 + +2567254-2567296 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2567296-2567338 SPI: COPI data: D0 : DMP Enable; FIFO Enable; Reset I2C peripheral module and put the serial interface in SPI mode only + +2567387-2567429 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2567429-2567471 SPI: COPI data: 47 : Disable pressure; all gyro axes + +2567520-2567562 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2567562-2567604 SPI: COPI data: D0 : DMP Enable; FIFO Enable; Reset I2C peripheral module and put the serial interface in SPI mode only + +2567665-2567707 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2567707-2567749 SPI: COPI data: 40 : DATA_OUT_CTL1 (4 * 16) + +2567793-2567835 SPI: COPI data: 7D : Set DATA_OUT_CTL1 to 0x0000 +2567835-2567877 SPI: COPI data: 00 +2567877-2567919 SPI: COPI data: 00 + +2567969-2568013 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2568011-2568055 SPI: COPI data: 4C : DATA_INTR_CTL (4 * 16 + 12) + +2568097-2568139 SPI: COPI data: 7D : Set DATA_INTR_CTL to 0x0000 +2568139-2568181 SPI: COPI data: 00 +2568181-2568223 SPI: COPI data: 00 + +2568275-2568319 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2568317-2568360 SPI: COPI data: 42 : DATA_OUT_CTL2 (4 * 16 + 2) + +2568403-2568447 SPI: COPI data: 7D : Set DATA_OUT_CTL2 to 0x0000 +2568445-2568489 SPI: COPI data: 00 +2568487-2568531 SPI: COPI data: 00 + +2568582-2568624 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2568624-2568666 SPI: COPI data: 4E : MOTION_EVENT_CTL (4 * 16 + 14) + +2568710-2568752 SPI: COPI data: 7D : Set MOTION_EVENT_CTL to 0x0000 +2568752-2568794 SPI: COPI data: 00 +2568794-2568836 SPI: COPI data: 00 + +2568932-2568974 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2568974-2569016 SPI: COPI data: 7F : Disable pressure; all accel axes; all gyro axes + +2569063-2569105 SPI: COPI data: 06 : Write Bank 0 Reg 0x07 PWR_MGMT_1 +2569105-2569147 SPI: COPI data: 41 : Sleep; Auto clock + +2569401-2569443 SPI: COPI data: 06 : Write Bank 0 Reg 0x07 PWR_MGMT_1 +2569443-2569485 SPI: COPI data: 01 : Auto clock + +2569732-2569776 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2569774-2569818 SPI: COPI data: 7F : Disable pressure; all accel axes; all gyro axes + +2569867-2569911 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2569909-2569953 SPI: COPI data: 8A : DATA_RDY_STATUS (8 * 16 + 10) + +2569995-2570037 SPI: COPI data: 7D : Set DATA_RDY_STATUS to 0x0000 +2570037-2570079 SPI: COPI data: 00 +2570079-2570121 SPI: COPI data: 00 + +2570169-2570211 SPI: COPI data: 06 +2570211-2570253 SPI: COPI data: 21 + +2570307-2570349 SPI: COPI data: 06 +2570349-2570391 SPI: COPI data: 01 + +2570637-2570679 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2570679-2570721 SPI: COPI data: D0 : DMP Enable; FIFO Enable; Reset I2C peripheral module and put the serial interface in SPI mode only + +2570770-2570812 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2570812-2570854 SPI: COPI data: 47 : Disable pressure; all gyro axes + +2570902-2570946 SPI: COPI data: 03 : Write Bank 0 Reg 0x03 USER_CTRL +2570944-2570988 SPI: COPI data: D0 : DMP Enable; FIFO Enable; Reset I2C peripheral module and put the serial interface in SPI mode only + +2571047-2571089 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2571089-2571131 SPI: COPI data: 40 : DATA_OUT_CTL1 (4 * 16) + +2571176-2571218 SPI: COPI data: 7D : Set DATA_OUT_CTL1 to 0x0808 (Quat6 + Header 2) +2571218-2571260 SPI: COPI data: 08 +2571260-2571302 SPI: COPI data: 08 + +2571353-2571395 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2571395-2571437 SPI: COPI data: 4C : DATA_INTR_CTL (4 * 16 + 12) + +2571481-2571523 SPI: COPI data: 7D : Set DATA_INTR_CTL to 0x0808 +2571523-2571565 SPI: COPI data: 08 +2571565-2571607 SPI: COPI data: 08 + +2571659-2571703 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2571701-2571745 SPI: COPI data: 42 : DATA_OUT_CTL2 (4 * 16 + 2) + +2571787-2571829 SPI: COPI data: 7D : Set DATA_OUT_CTL2 to 0x0000 +2571829-2571871 SPI: COPI data: 00 +2571871-2571913 SPI: COPI data: 00 + +2571966-2572008 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2572008-2572050 SPI: COPI data: 4E : MOTION_EVENT_CTL (4 * 16 + 14) + +2572093-2572137 SPI: COPI data: 7D : Set MOTION_EVENT_CTL to 0x0300 (Gyro_Calibr + Accel_Calibr) +2572135-2572179 SPI: COPI data: 03 +2572177-2572221 SPI: COPI data: 00 + +2572310-2572352 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2572352-2572394 SPI: COPI data: 01 : Bank 0x01 + +2572438-2572480 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2572480-2572522 SPI: COPI data: 0C : ACCEL_ONLY_GAIN (16 * 16 + 12) + +2572565-2572609 SPI: COPI data: 7D : Set ACCEL_ONLY_GAIN to 0x00E8BA2E (225Hz) +2572607-2572651 SPI: COPI data: 00 +2572649-2572693 SPI: COPI data: E8 +2572691-2572735 SPI: COPI data: BA +2572733-2572777 SPI: COPI data: 2E + +2572827-2572869 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2572869-2572911 SPI: COPI data: 05 : Bank 0x05 + +2572954-2572998 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2572996-2573040 SPI: COPI data: B0 : ACCEL_ALPHA_VAR (91 * 16) + +2573082-2573124 SPI: COPI data: 7D : Set ACCEL_ALPHA_VAR to 0x3D27D27D (225Hz) +2573124-2573166 SPI: COPI data: 3D +2573166-2573208 SPI: COPI data: 27 +2573208-2573250 SPI: COPI data: D2 +2573250-2573292 SPI: COPI data: 7D + +2573342-2573384 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2573384-2573426 SPI: COPI data: C0 : ACCEL_A_VAR (92 * 16) + +2573470-2573512 SPI: COPI data: 7D : Set ACCEL_A_VAR to 0x02D82D83 (225Hz) +2573512-2573554 SPI: COPI data: 02 +2573554-2573596 SPI: COPI data: D8 +2573596-2573638 SPI: COPI data: 2D +2573638-2573680 SPI: COPI data: 83 + +2573729-2573773 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2573771-2573815 SPI: COPI data: E4 : ACCEL_CAL_INIT (94 * 16 + 4) + +2573857-2573899 SPI: COPI data: 7D : Set ACCEL_CAL_INIT to 0x0000 +2573899-2573941 SPI: COPI data: 00 +2573941-2573983 SPI: COPI data: 00 + +2574034-2574078 SPI: COPI data: FF +2574076-2574120 SPI: CIPO data: 00 + +2574162-2574204 SPI: COPI data: 7F +2574204-2574246 SPI: COPI data: 20 + +2574291-2574333 SPI: COPI data: 10 : Set Bank 2 Reg 0x10 ACCEL_SMPLRT_DIV_1 to 0x0004 +2574333-2574375 SPI: COPI data: 00 +2574375-2574417 SPI: COPI data: 04 + +2574476-2574518 SPI: COPI data: 00 : Set Bank 2 Reg 0x00 GYRO_SMPLRT_DIV to 0x04 (ODR = 1100/5 = 220Hz) +2574518-2574562 SPI: COPI data: 04 + +2574620-2574662 SPI: COPI data: FF +2574662-2574704 SPI: CIPO data: 20 + +2574747-2574791 SPI: COPI data: 7F +2574789-2574833 SPI: COPI data: 00 + +2574877-2574919 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2574919-2574961 SPI: COPI data: 00 : Bank 0x00 + +2575005-2575047 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2575047-2575089 SPI: COPI data: AC : ODR_QUAT6 (10 * 16 + 12) + +2575132-2575176 SPI: COPI data: 7D : Set ODR_QUAT6 to 0x0000 +2575174-2575218 SPI: COPI data: 00 +2575216-2575260 SPI: COPI data: 00 + +2575323-2575367 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2575365-2575409 SPI: COPI data: 01 : Bank 0x01 + +2575451-2575495 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2575493-2575537 SPI: COPI data: 30 : GYRO_SF (19 * 16) + +2575579-2575623 SPI: COPI data: 7D : Set GYRO_SF to 0x09DBEF0D (225Hz) +2575621-2575665 SPI: COPI data: 09 +2575663-2575707 SPI: COPI data: DB +2575705-2575749 SPI: COPI data: EF +2575747-2575791 SPI: COPI data: 0D + +2575840-2575884 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2575882-2575926 SPI: COPI data: 40 : Disable pressure (all accel and gyro axes enabled) + +2575975-2576017 SPI: COPI data: 7E : Write Bank 0 Reg 0x7E Memory Bank Select +2576017-2576059 SPI: COPI data: 00 : Bank 0x00 + +2576103-2576145 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2576145-2576187 SPI: COPI data: 8A : DATA_RDY_STATUS (8 * 16 + 10) + +2576230-2576274 SPI: COPI data: 7D : Set DATA_RDY_STATUS to 0x0003 (gyro and accel samples) +2576272-2576316 SPI: COPI data: 00 +2576314-2576358 SPI: COPI data: 03 + +2576404-2576448 SPI: COPI data: 06 +2576446-2576490 SPI: COPI data: 21 + +2576554-2576596 SPI: COPI data: 06 +2576596-2576638 SPI: COPI data: 01 + +2576885-2576927 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2576927-2576969 SPI: COPI data: 40 : DATA_OUT_CTL1 (4 * 16) + +2577012-2577056 SPI: COPI data: 7D : Set DATA_OUT_CTL1 to 0x0808 +2577054-2577098 SPI: COPI data: 08 +2577096-2577140 SPI: COPI data: 08 + +2577189-2577233 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2577231-2577275 SPI: COPI data: 4C : DATA_INTR_CTL (4 * 16 + 12) + +2577317-2577359 SPI: COPI data: 7D : Set DATA_INTR_CTL to 0x0808 +2577359-2577401 SPI: COPI data: 08 +2577401-2577443 SPI: COPI data: 08 + +2577495-2577539 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2577537-2577581 SPI: COPI data: 42 : DATA_OUT_CTL2 (4 * 16 + 2) + +2577623-2577667 SPI: COPI data: 7D : Set DATA_OUT_CTL2 to 0x0000 +2577665-2577709 SPI: COPI data: 00 +2577707-2577751 SPI: COPI data: 00 + +2577802-2577844 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2577844-2577886 SPI: COPI data: 4E : MOTION_EVENT_CTL (4 * 16 + 14) + +2577930-2577972 SPI: COPI data: 7D : Set MOTION_EVENT_CTL to 0x0300 (Gyro_Calibr + Accel_Calibr) +2577972-2578014 SPI: COPI data: 03 +2578014-2578056 SPI: COPI data: 00 + +2578157-2578199 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2578199-2578241 SPI: COPI data: AC : ODR_QUAT6 (10 * 16 + 12) + +2578285-2578327 SPI: COPI data: 7D : Set ODR_QUAT6 to 0x0000 +2578327-2578369 SPI: COPI data: 00 +2578369-2578411 SPI: COPI data: 00 + +2578476-2578520 SPI: COPI data: 07 : Write Bank 0 Reg 0x07 PWR_MGMT_2 +2578518-2578562 SPI: COPI data: 40 : Disable pressure (all accel and gyro axes are enabled) + +2578611-2578655 SPI: COPI data: 7C : Write Bank 0 Reg 0x7C Memory Start Address +2578653-2578697 SPI: COPI data: 8A : DATA_RDY_STATUS (8 * 16 + 10) + +2578739-2578781 SPI: COPI data: 7D : Set DATA_RDY_STATUS to 0x0003 (gyro + accel) +2578781-2578823 SPI: COPI data: 00 +2578823-2578865 SPI: COPI data: 03 + +2578913-2578955 SPI: COPI data: 06 : Write Bank 0 Reg 0x06 PWR_MGMT_1 +2578955-2578997 SPI: COPI data: 21 : Set PWR_MGMT_1 : Turn on low power; Auto clock best available + +2579049-2579091 SPI: COPI data: 99 : Read Bank 0 Reg 0x19 INT_STATUS +2579091-2579133 SPI: CIPO data: 88 : Reserved + Wake_On_Motion Int + +2579181-2579225 SPI: COPI data: 98 : Read Bank 0 Reg 0x18 DMP_INT_STATUS +2579223-2579267 SPI: CIPO data: 00 + +2579320-2579362 SPI: COPI data: 99 : Read Bank 0 Reg 0x19 INT_STATUS +2579362-2579404 SPI: CIPO data: 00 + +2579452-2579496 SPI: COPI data: 98 : Read Bank 0 Reg 0x18 DMP_INT_STATUS +2579494-2579538 SPI: CIPO data: 00 + +... + +... + +2652310-2652352 SPI: COPI data: 99 : Read Bank 0 Reg 0x19 INT_STATUS +2652352-2652394 SPI: CIPO data: 02 : DMP_INT1 – Indicates the DMP has generated INT1 interrupt. + +2652442-2652484 SPI: COPI data: 98 : Read Bank 0 Reg 0x18 DMP_INT_STATUS +2652484-2652526 SPI: CIPO data: 01 + +2652583-2652625 SPI: COPI data: F0 : Read Bank 0 Reg 0x70 FIFO_COUNTH +2652625-2652667 SPI: CIPO data: 00 : FIFO contains 16 bytes +2652667-2652709 SPI: CIPO data: 10 + +2652759-2652801 SPI: COPI data: F2 : Read Bank 0 Reg 0x72 FIFO_R_W +2652801-2652843 SPI: CIPO data: 08 : Header: Quat6 +2652843-2652885 SPI: CIPO data: 00 : Header: +2652885-2652927 SPI: CIPO data: FF : Quat6: Q1 +2652927-2652969 SPI: CIPO data: FF : Quat6: Q1 +2652969-2653011 SPI: CIPO data: AE : Quat6: Q1 +2653011-2653053 SPI: CIPO data: 9B : Quat6: Q1 +2653053-2653095 SPI: CIPO data: 00 : Quat6: Q2 +2653095-2653137 SPI: CIPO data: 00 : Quat6: Q2 +2653137-2653179 SPI: CIPO data: 4D : Quat6: Q2 +2653179-2653221 SPI: CIPO data: 83 : Quat6: Q2 +2653221-2653263 SPI: CIPO data: 00 : Quat6: Q3 +2653263-2653305 SPI: CIPO data: 00 : Quat6: Q3 +2653305-2653347 SPI: CIPO data: 00 : Quat6: Q3 +2653347-2653389 SPI: CIPO data: 00 : Quat6: Q3 +2653389-2653431 SPI: CIPO data: 00 : Footer: Gyro count +2653431-2653473 SPI: CIPO data: 01 : Footer: Gyro count + +2653606-2653648 SPI: COPI data: 99 +2653648-2653690 SPI: CIPO data: 00 + +2653739-2653781 SPI: COPI data: 98 +2653781-2653823 SPI: CIPO data: 00 + +... + +``` diff --git a/lib/ICM-20948/ISSUE_TEMPLATE.md b/lib/ICM-20948/ISSUE_TEMPLATE.md new file mode 100644 index 0000000..9f691f4 --- /dev/null +++ b/lib/ICM-20948/ISSUE_TEMPLATE.md @@ -0,0 +1,18 @@ +### Subject of the issue +Describe your issue here. + +### Your workbench +* What platform are you using? +* What version of the device are you using? Is there a firmware version? +* How is the device wired to your platform? +* How is everything being powered? +* Are there any additional details that may help us help you? + +### Steps to reproduce +Tell us how to reproduce this issue. Please post stripped down example code demonstrating your issue to a gist. + +### Expected behaviour +Tell us what should happen + +### Actual behaviour +Tell us what happens instead diff --git a/lib/ICM-20948/License.md b/lib/ICM-20948/License.md new file mode 100644 index 0000000..e64bd4e --- /dev/null +++ b/lib/ICM-20948/License.md @@ -0,0 +1,55 @@ +SparkFun License Information +============================ + +SparkFun uses two different licenses for our files — one for hardware and one for code. + +Hardware +--------- + +**SparkFun hardware is released under [Creative Commons Share-alike 4.0 International](http://creativecommons.org/licenses/by-sa/4.0/).** + +Note: This is a human-readable summary of (and not a substitute for) the [license](http://creativecommons.org/licenses/by-sa/4.0/legalcode). + +You are free to: + +Share — copy and redistribute the material in any medium or format +Adapt — remix, transform, and build upon the material +for any purpose, even commercially. +The licensor cannot revoke these freedoms as long as you follow the license terms. +Under the following terms: + +Attribution — You must give appropriate credit, provide a link to the license, and indicate if changes were made. You may do so in any reasonable manner, but not in any way that suggests the licensor endorses you or your use. +ShareAlike — If you remix, transform, or build upon the material, you must distribute your contributions under the same license as the original. +No additional restrictions — You may not apply legal terms or technological measures that legally restrict others from doing anything the license permits. +Notices: + +You do not have to comply with the license for elements of the material in the public domain or where your use is permitted by an applicable exception or limitation. +No warranties are given. The license may not give you all of the permissions necessary for your intended use. For example, other rights such as publicity, privacy, or moral rights may limit how you use the material. + + +Code +-------- + +**SparkFun code, firmware, and software is released under the MIT License(http://opensource.org/licenses/MIT).** + +The MIT License (MIT) + +Copyright (c) 2016 SparkFun Electronics + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/lib/ICM-20948/README.md b/lib/ICM-20948/README.md new file mode 100644 index 0000000..90df95a --- /dev/null +++ b/lib/ICM-20948/README.md @@ -0,0 +1,39 @@ +# SparkFun ICM-20948 Arduino Library + +This is the SparkFun library for the TDK InvenSense ICM-20948 Inertial Measurement Unit 9-Degree Of Freedom sensor as used on the [SparkFun 9DoF IMU Breakout - ICM-20948 (Qwiic)](https://www.sparkfun.com/products/15335). + +Version 1.2 of the library includes support for the InvenSense Digital Motion Processor (DMP™). You can find further details in [DMP.md](./DMP.md). + +## Contributing + +If you would like to contribute to this library: please do, we truly appreciate it, but please follow [these guidelines](./CONTRIBUTING.md). Thanks! + +## Repository Contents + +* [**/examples**](./examples) - Example sketches for the library (.ino). Run these from the Arduino IDE. +* [**/src**](./src) - Source files for the library (.cpp, .h). +* [**keywords.txt**](./keywords.txt) - Keywords from this library that will be highlighted in the Arduino IDE. +* [**library.properties**](./library.properties) - General library properties for the Arduino package manager. +* [**CONTRIBUTING.md**](./CONTRIBUTING.md) - Guidelines on how to contribute to this library. +* [**DMP.md**](./DMP.md) - Information about the InvenSense Digital Motion Processor (DMP™) + +## Documentation + +* **[Hookup Guide](https://learn.sparkfun.com/tutorials/sparkfun-9dof-imu-icm-20948-breakout-hookup-guide)** - Basic hookup guide for the SparkFun 9DoF IMU Breakout. +* **[Installing an Arduino Library Guide](https://learn.sparkfun.com/tutorials/installing-an-arduino-library)** - Basic information on how to install an Arduino library. + +## Products that use this Library + +* [SparkFun 9DoF IMU Breakout - ICM-20948 (Qwiic) - SEN-15335](https://www.sparkfun.com/products/15335) +* [SparkFun OpenLog Artemis - DEV-16832](https://www.sparkfun.com/products/16832) +* [SparkFun MicroMod Asset Tracker Carrier Board - DEV-17272](https://www.sparkfun.com/products/17272) + +## License Information + +This product is _**open source**_! + +Please see the included [License.md](./License.md) for more information. + +Distributed as-is; no warranty is given. + +- Your friends at SparkFun. diff --git a/lib/ICM-20948/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino b/lib/ICM-20948/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino new file mode 100644 index 0000000..467cc84 --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example10_DMP_FastMultipleSensors/Example10_DMP_FastMultipleSensors.ino @@ -0,0 +1,491 @@ +/**************************************************************** + * Example10_DMP_FastMultipleSensors.ino + * ICM 20948 Arduino Library Demo + * Initialize the DMP based on the TDK InvenSense ICM20948_eMD_nucleo_1.0 example-icm20948 + * Paul Clark, April 25th, 2021 + * Based on original code by: + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * ** This example is based on InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + * ** We are grateful to InvenSense for sharing this with us. + * + * ** Important note: by default the DMP functionality is disabled in the library + * ** as the DMP firmware takes up 14301 Bytes of program memory. + * ** To use the DMP, you will need to: + * ** Edit ICM_20948_C.h + * ** Uncomment line 29: #define ICM_20948_USE_DMP + * ** Save changes + * ** If you are using Windows, you can find ICM_20948_C.h in: + * ** Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); // Start the serial console + SERIAL_PORT.println(F("ICM-20948 Example")); + + delay(100); + + while (SERIAL_PORT.available()) // Make sure the serial RX buffer is empty + SERIAL_PORT.read(); + + SERIAL_PORT.println(F("Press any key to continue...")); + + while (!SERIAL_PORT.available()) // Wait for the user to press a key (send any serial character) + ; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + + // Initialize the ICM-20948 + // If the DMP is enabled, .begin performs a minimal startup. We need to configure the sample mode etc. manually. +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println(F("Trying again...")); + delay(500); + } + else + { + initialized = true; + } + } + + SERIAL_PORT.println(F("Device connected!")); + + bool success = true; // Use success to show if the DMP configuration was successful + + // Initialize the DMP. initializeDMP is a weak function. In this example we overwrite it to change the sample rate (see below) + success &= (myICM.initializeDMP() == ICM_20948_Stat_Ok); + + // DMP sensor options are defined in ICM_20948_DMP.h + // INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) + // INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) + // INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) + // INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) + // INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) + // INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) + + // Enable the DMP Game Rotation Vector sensor (Quat6) + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR) == ICM_20948_Stat_Ok); + + // Enable additional sensors / features + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_GYROSCOPE) == ICM_20948_Stat_Ok); + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_ACCELEROMETER) == ICM_20948_Stat_Ok); + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED) == ICM_20948_Stat_Ok); + + // Configuring DMP to output data at multiple ODRs: + // DMP is capable of outputting multiple sensor data at different rates to FIFO. + // Setting value can be calculated as follows: + // Value = (DMP running rate / ODR ) - 1 + // E.g. For a 225Hz ODR rate when DMP is running at 225Hz, value = (225/225) - 1 = 0. + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, 0) == ICM_20948_Stat_Ok); // Set to 225Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0) == ICM_20948_Stat_Ok); // Set to 225Hz + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 0) == ICM_20948_Stat_Ok); // Set to 225Hz + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 0) == ICM_20948_Stat_Ok); // Set to 225Hz + + // Enable the FIFO + success &= (myICM.enableFIFO() == ICM_20948_Stat_Ok); + + // Enable the DMP + success &= (myICM.enableDMP() == ICM_20948_Stat_Ok); + + // Reset DMP + success &= (myICM.resetDMP() == ICM_20948_Stat_Ok); + + // Reset FIFO + success &= (myICM.resetFIFO() == ICM_20948_Stat_Ok); + + // Check success + if (success) + { + SERIAL_PORT.println(F("DMP enabled!")); + } + else + { + SERIAL_PORT.println(F("Enable DMP failed!")); + SERIAL_PORT.println(F("Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + while (1) + ; // Do nothing more + } +} + +void loop() +{ + // Read any DMP data waiting in the FIFO + // Note: + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFONoDataAvail if no data is available. + // If data is available, readDMPdataFromFIFO will attempt to read _one_ frame of DMP data. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOIncompleteData if a frame was present but was incomplete + // readDMPdataFromFIFO will return ICM_20948_Stat_Ok if a valid frame was read. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOMoreDataAvail if a valid frame was read _and_ the FIFO contains more (unread) data. + icm_20948_DMP_data_t data; + myICM.readDMPdataFromFIFO(&data); + + if ((myICM.status == ICM_20948_Stat_Ok) || (myICM.status == ICM_20948_Stat_FIFOMoreDataAvail)) // Was valid data available? + { + //SERIAL_PORT.print(F("Received data! Header: 0x")); // Print the header in HEX so we can see what data is arriving in the FIFO + //if ( data.header < 0x1000) SERIAL_PORT.print( "0" ); // Pad the zeros + //if ( data.header < 0x100) SERIAL_PORT.print( "0" ); + //if ( data.header < 0x10) SERIAL_PORT.print( "0" ); + //SERIAL_PORT.println( data.header, HEX ); + + if ((data.header & DMP_header_bitmap_Quat6) > 0) // Check for GRV data (Quat6) + { + // Q0 value is computed from this equation: Q0^2 + Q1^2 + Q2^2 + Q3^2 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + + //SERIAL_PORT.printf("Quat6 data is: Q1:%ld Q2:%ld Q3:%ld\r\n", data.Quat6.Data.Q1, data.Quat6.Data.Q2, data.Quat6.Data.Q3); + + // Scale to +/- 1 + double q1 = ((double)data.Quat6.Data.Q1) / 1073741824.0; // Convert to double. Divide by 2^30 + double q2 = ((double)data.Quat6.Data.Q2) / 1073741824.0; // Convert to double. Divide by 2^30 + double q3 = ((double)data.Quat6.Data.Q3) / 1073741824.0; // Convert to double. Divide by 2^30 + + SERIAL_PORT.print(F("Q1:")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(" Q2:")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(" Q3:")); + SERIAL_PORT.println(q3, 3); + } + + if ((data.header & DMP_header_bitmap_Accel) > 0) // Check for Accel + { + float acc_x = (float)data.Raw_Accel.Data.X; // Extract the raw accelerometer data + float acc_y = (float)data.Raw_Accel.Data.Y; + float acc_z = (float)data.Raw_Accel.Data.Z; + + SERIAL_PORT.print(F("Accel: X:")); + SERIAL_PORT.print(acc_x); + SERIAL_PORT.print(F(" Y:")); + SERIAL_PORT.print(acc_y); + SERIAL_PORT.print(F(" Z:")); + SERIAL_PORT.println(acc_z); + } + + // if ( (data.header & DMP_header_bitmap_Gyro) > 0 ) // Check for Gyro + // { + // float x = (float)data.Raw_Gyro.Data.X; // Extract the raw gyro data + // float y = (float)data.Raw_Gyro.Data.Y; + // float z = (float)data.Raw_Gyro.Data.Z; + // + // SERIAL_PORT.print(F("Gyro: X:")); + // SERIAL_PORT.print(x); + // SERIAL_PORT.print(F(" Y:")); + // SERIAL_PORT.print(y); + // SERIAL_PORT.print(F(" Z:")); + // SERIAL_PORT.println(z); + // } + // + // if ( (data.header & DMP_header_bitmap_Compass) > 0 ) // Check for Compass + // { + // float x = (float)data.Compass.Data.X; // Extract the compass data + // float y = (float)data.Compass.Data.Y; + // float z = (float)data.Compass.Data.Z; + // + // SERIAL_PORT.print(F("Compass: X:")); + // SERIAL_PORT.print(x); + // SERIAL_PORT.print(F(" Y:")); + // SERIAL_PORT.print(y); + // SERIAL_PORT.print(F(" Z:")); + // SERIAL_PORT.println(z); + // } + } + + if (myICM.status != ICM_20948_Stat_FIFOMoreDataAvail) // If more data is available then we should read it right away - and not delay + { + delay(1); // Keep this short! + } +} + +// initializeDMP is a weak function. Let's overwrite it so we can increase the sample rate +ICM_20948_Status_e ICM_20948::initializeDMP(void) +{ + // The ICM-20948 is awake and ready but hasn't been configured. Let's step through the configuration + // sequence from InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + + ICM_20948_Status_e result = ICM_20948_Stat_Ok; // Use result and worstResult to show if the configuration was successful + ICM_20948_Status_e worstResult = ICM_20948_Stat_Ok; + + // Normally, when the DMP is not enabled, startupMagnetometer (called by startupDefault, which is called by begin) configures the AK09916 magnetometer + // to run at 100Hz by setting the CNTL2 register (0x31) to 0x08. Then the ICM20948's I2C_SLV0 is configured to read + // nine bytes from the mag every sample, starting from the STATUS1 register (0x10). ST1 includes the DRDY (Data Ready) bit. + // Next are the six magnetometer readings (little endian). After a dummy byte, the STATUS2 register (0x18) contains the HOFL (Overflow) bit. + // + // But looking very closely at the InvenSense example code, we can see in inv_icm20948_resume_akm (in Icm20948AuxCompassAkm.c) that, + // when the DMP is running, the magnetometer is set to Single Measurement (SM) mode and that ten bytes are read, starting from the reserved + // RSV2 register (0x03). The datasheet does not define what registers 0x04 to 0x0C contain. There is definitely some secret sauce in here... + // The magnetometer data appears to be big endian (not little endian like the HX/Y/Z registers) and starts at register 0x04. + // We had to examine the I2C traffic between the master and the AK09916 on the AUX_DA and AUX_CL pins to discover this... + // + // So, we need to set up I2C_SLV0 to do the ten byte reading. The parameters passed to i2cControllerConfigurePeripheral are: + // 0: use I2C_SLV0 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_RSV2: we start reading here (0x03). Secret sauce... + // 10: we read 10 bytes each cycle + // true: set the I2C_SLV0_RNW ReadNotWrite bit so we read the 10 bytes (not write them) + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit to enable reading from the peripheral at the sample rate + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // true: set the I2C_SLV0_CTRL I2C_SLV0_GRP bit to show the register pairing starts at byte 1+2 (copied from inv_icm20948_resume_akm) + // true: set the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW to byte-swap the data from the mag (copied from inv_icm20948_resume_akm) + result = i2cControllerConfigurePeripheral(0, MAG_AK09916_I2C_ADDR, AK09916_REG_RSV2, 10, true, true, false, true, true); if (result > worstResult) worstResult = result; + // + // We also need to set up I2C_SLV1 to do the Single Measurement triggering: + // 1: use I2C_SLV1 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_CNTL2: we start writing here (0x31) + // 1: not sure why, but the write does not happen if this is set to zero + // false: clear the I2C_SLV0_RNW ReadNotWrite bit so we write the dataOut byte + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit. Not sure why, but the write does not happen if this is clear + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // false: clear the I2C_SLV0_CTRL I2C_SLV0_GRP bit + // false: clear the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW bit + // AK09916_mode_single: tell I2C_SLV1 to write the Single Measurement command each sample + result = i2cControllerConfigurePeripheral(1, MAG_AK09916_I2C_ADDR, AK09916_REG_CNTL2, 1, false, true, false, false, false, AK09916_mode_single); if (result > worstResult) worstResult = result; + + // Set the I2C Master ODR configuration + // It is not clear why we need to do this... But it appears to be essential! From the datasheet: + // "I2C_MST_ODR_CONFIG[3:0]: ODR configuration for external sensor when gyroscope and accelerometer are disabled. + // ODR is computed as follows: 1.1 kHz/(2^((odr_config[3:0])) ) + // When gyroscope is enabled, all sensors (including I2C_MASTER) use the gyroscope ODR. + // If gyroscope is disabled, then all sensors (including I2C_MASTER) use the accelerometer ODR." + // Since both gyro and accel are running, setting this register should have no effect. But it does. Maybe because the Gyro and Accel are placed in Low Power Mode (cycled)? + // You can see by monitoring the Aux I2C pins that the next three lines reduce the bus traffic (magnetometer reads) from 1125Hz to the chosen rate: 68.75Hz in this case. + result = setBank(3); if (result > worstResult) worstResult = result; // Select Bank 3 + uint8_t mstODRconfig = 0x04; // Set the ODR configuration to 1100/2^4 = 68.75Hz + result = write(AGB3_REG_I2C_MST_ODR_CONFIG, &mstODRconfig, 1); if (result > worstResult) worstResult = result; // Write one byte to the I2C_MST_ODR_CONFIG register + + // Configure clock source through PWR_MGMT_1 + // ICM_20948_Clock_Auto selects the best available clock source – PLL if ready, else use the Internal oscillator + result = setClockSource(ICM_20948_Clock_Auto); if (result > worstResult) worstResult = result; // This is shorthand: success will be set to false if setClockSource fails + + // Enable accel and gyro sensors through PWR_MGMT_2 + // Enable Accelerometer (all axes) and Gyroscope (all axes) by writing zero to PWR_MGMT_2 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t pwrMgmt2 = 0x40; // Set the reserved bit 6 (pressure sensor disable?) + result = write(AGB0_REG_PWR_MGMT_2, &pwrMgmt2, 1); if (result > worstResult) worstResult = result; // Write one byte to the PWR_MGMT_2 register + + // Place _only_ I2C_Master in Low Power Mode (cycled) via LP_CONFIG + // The InvenSense Nucleo example initially puts the accel and gyro into low power mode too, but then later updates LP_CONFIG so only the I2C_Master is in Low Power Mode + result = setSampleMode(ICM_20948_Internal_Mst, ICM_20948_Sample_Mode_Cycled); if (result > worstResult) worstResult = result; + + // Disable the FIFO + result = enableFIFO(false); if (result > worstResult) worstResult = result; + + // Disable the DMP + result = enableDMP(false); if (result > worstResult) worstResult = result; + + // Set Gyro FSR (Full scale range) to 2000dps through GYRO_CONFIG_1 + // Set Accel FSR (Full scale range) to 4g through ACCEL_CONFIG + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + myFSS.a = gpm4; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + myFSS.g = dps2000; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + result = setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); if (result > worstResult) worstResult = result; + + // The InvenSense Nucleo code also enables the gyro DLPF (but leaves GYRO_DLPFCFG set to zero = 196.6Hz (3dB)) + // We found this by going through the SPI data generated by ZaneL's Teensy-ICM-20948 library byte by byte... + // The gyro DLPF is enabled by default (GYRO_CONFIG_1 = 0x01) so the following line should have no effect, but we'll include it anyway + result = enableDLPF(ICM_20948_Internal_Gyr, true); if (result > worstResult) worstResult = result; + + // Enable interrupt for FIFO overflow from FIFOs through INT_ENABLE_2 + // If we see this interrupt, we'll need to reset the FIFO + //result = intEnableOverflowFIFO( 0x1F ); if (result > worstResult) worstResult = result; // Enable the interrupt on all FIFOs + + // Turn off what goes into the FIFO through FIFO_EN_1, FIFO_EN_2 + // Stop the peripheral data from being written to the FIFO by writing zero to FIFO_EN_1 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t zero = 0; + result = write(AGB0_REG_FIFO_EN_1, &zero, 1); if (result > worstResult) worstResult = result; + // Stop the accelerometer, gyro and temperature data from being written to the FIFO by writing zero to FIFO_EN_2 + result = write(AGB0_REG_FIFO_EN_2, &zero, 1); if (result > worstResult) worstResult = result; + + // Turn off data ready interrupt through INT_ENABLE_1 + result = intEnableRawDataReady(false); if (result > worstResult) worstResult = result; + + // Reset FIFO through FIFO_RST + result = resetFIFO(); if (result > worstResult) worstResult = result; + + // Set gyro sample rate divider with GYRO_SMPLRT_DIV + // Set accel sample rate divider with ACCEL_SMPLRT_DIV_2 + ICM_20948_smplrt_t mySmplrt; + //mySmplrt.g = 19; // ODR is computed as follows: 1.1 kHz/(1+GYRO_SMPLRT_DIV[7:0]). 19 = 55Hz. InvenSense Nucleo example uses 19 (0x13). + //mySmplrt.a = 19; // ODR is computed as follows: 1.125 kHz/(1+ACCEL_SMPLRT_DIV[11:0]). 19 = 56.25Hz. InvenSense Nucleo example uses 19 (0x13). + mySmplrt.g = 4; // 225Hz + mySmplrt.a = 4; // 225Hz + //mySmplrt.g = 8; // 112Hz + //mySmplrt.a = 8; // 112Hz + result = setSampleRate((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), mySmplrt); if (result > worstResult) worstResult = result; + + // Setup DMP start address through PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Now load the DMP firmware + result = loadDMPFirmware(); if (result > worstResult) worstResult = result; + + // Write the 2 byte Firmware Start Value to ICM PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Set the Hardware Fix Disable register to 0x48 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fix = 0x48; + result = write(AGB0_REG_HW_FIX_DISABLE, &fix, 1); if (result > worstResult) worstResult = result; + + // Set the Single FIFO Priority Select register to 0xE4 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fifoPrio = 0xE4; + result = write(AGB0_REG_SINGLE_FIFO_PRIORITY_SEL, &fifoPrio, 1); if (result > worstResult) worstResult = result; + + // Configure Accel scaling to DMP + // The DMP scales accel raw data internally to align 1g as 2^25 + // In order to align internal accel raw data 2^25 = 1g write 0x04000000 when FSR is 4g + const unsigned char accScale[4] = {0x04, 0x00, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE, 4, &accScale[0]); if (result > worstResult) worstResult = result; // Write accScale to ACC_SCALE DMP register + // In order to output hardware unit data as configured FSR write 0x00040000 when FSR is 4g + const unsigned char accScale2[4] = {0x00, 0x04, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE2, 4, &accScale2[0]); if (result > worstResult) worstResult = result; // Write accScale2 to ACC_SCALE2 DMP register + + // Configure Compass mount matrix and scale to DMP + // The mount matrix write to DMP register is used to align the compass axes with accel/gyro. + // This mechanism is also used to convert hardware unit to uT. The value is expressed as 1uT = 2^30. + // Each compass axis will be converted as below: + // X = raw_x * CPASS_MTX_00 + raw_y * CPASS_MTX_01 + raw_z * CPASS_MTX_02 + // Y = raw_x * CPASS_MTX_10 + raw_y * CPASS_MTX_11 + raw_z * CPASS_MTX_12 + // Z = raw_x * CPASS_MTX_20 + raw_y * CPASS_MTX_21 + raw_z * CPASS_MTX_22 + // The AK09916 produces a 16-bit signed output in the range +/-32752 corresponding to +/-4912uT. 1uT = 6.66 ADU. + // 2^30 / 6.66666 = 161061273 = 0x9999999 + const unsigned char mountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char mountMultiplierPlus[4] = {0x09, 0x99, 0x99, 0x99}; // Value taken from InvenSense Nucleo example + const unsigned char mountMultiplierMinus[4] = {0xF6, 0x66, 0x66, 0x67}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(CPASS_MTX_00, 4, &mountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_01, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_02, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_10, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_11, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_12, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_20, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_21, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_22, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + + // Configure the B2S Mounting Matrix + const unsigned char b2sMountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char b2sMountMultiplierPlus[4] = {0x40, 0x00, 0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(B2S_MTX_00, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_01, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_02, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_10, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_11, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_12, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_20, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_21, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_22, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + + // Configure the DMP Gyro Scaling Factor + // @param[in] gyro_div Value written to GYRO_SMPLRT_DIV register, where + // 0=1125Hz sample rate, 1=562.5Hz sample rate, ... 4=225Hz sample rate, ... + // 10=102.2727Hz sample rate, ... etc. + // @param[in] gyro_level 0=250 dps, 1=500 dps, 2=1000 dps, 3=2000 dps + result = setGyroSF(4, 3); if (result > worstResult) worstResult = result; // 4 = 225Hz (see above), 3 = 2000dps (see above) + + // Configure the Gyro full scale + // 2000dps : 2^28 + // 1000dps : 2^27 + // 500dps : 2^26 + // 250dps : 2^25 + const unsigned char gyroFullScale[4] = {0x10, 0x00, 0x00, 0x00}; // 2000dps : 2^28 + result = writeDMPmems(GYRO_FULLSCALE, 4, &gyroFullScale[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Only Gain: 15252014 (225Hz) 30504029 (112Hz) 61117001 (56Hz) + //const unsigned char accelOnlyGain[4] = {0x03, 0xA4, 0x92, 0x49}; // 56Hz + const unsigned char accelOnlyGain[4] = {0x00, 0xE8, 0xBA, 0x2E}; // 225Hz + //const unsigned char accelOnlyGain[4] = {0x01, 0xD1, 0x74, 0x5D}; // 112Hz + result = writeDMPmems(ACCEL_ONLY_GAIN, 4, &accelOnlyGain[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Alpha Var: 1026019965 (225Hz) 977872018 (112Hz) 882002213 (56Hz) + //const unsigned char accelAlphaVar[4] = {0x34, 0x92, 0x49, 0x25}; // 56Hz + const unsigned char accelAlphaVar[4] = {0x3D, 0x27, 0xD2, 0x7D}; // 225Hz + //const unsigned char accelAlphaVar[4] = {0x3A, 0x49, 0x24, 0x92}; // 112Hz + result = writeDMPmems(ACCEL_ALPHA_VAR, 4, &accelAlphaVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel A Var: 47721859 (225Hz) 95869806 (112Hz) 191739611 (56Hz) + //const unsigned char accelAVar[4] = {0x0B, 0x6D, 0xB6, 0xDB}; // 56Hz + const unsigned char accelAVar[4] = {0x02, 0xD8, 0x2D, 0x83}; // 225Hz + //const unsigned char accelAVar[4] = {0x05, 0xB6, 0xDB, 0x6E}; // 112Hz + result = writeDMPmems(ACCEL_A_VAR, 4, &accelAVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Cal Rate + const unsigned char accelCalRate[4] = {0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(ACCEL_CAL_RATE, 2, &accelCalRate[0]); if (result > worstResult) worstResult = result; + + // Configure the Compass Time Buffer. The I2C Master ODR Configuration (see above) sets the magnetometer read rate to 68.75Hz. + // Let's set the Compass Time Buffer to 69 (Hz). + const unsigned char compassRate[2] = {0x00, 0x45}; // 69Hz + result = writeDMPmems(CPASS_TIME_BUFFER, 2, &compassRate[0]); if (result > worstResult) worstResult = result; + + // Enable DMP interrupt + // This would be the most efficient way of getting the DMP data, instead of polling the FIFO + //result = intEnableDMP(true); if (result > worstResult) worstResult = result; + + return worstResult; +} diff --git a/lib/ICM-20948/examples/Arduino/Example1_Basics/Example1_Basics.ino b/lib/ICM-20948/examples/Arduino/Example1_Basics/Example1_Basics.ino new file mode 100644 index 0000000..4084b62 --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example1_Basics/Example1_Basics.ino @@ -0,0 +1,250 @@ +/**************************************************************** + * Example1_Basics.ino + * ICM 20948 Arduino Library Demo + * Use the default configuration to stream 9-axis IMU data + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU +#include +#include "wiring_private.h" + +TwoWire myWire(&sercom1, 11, 13); + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void printPaddedInt16b(int16_t val); +void printRawAGMT(ICM_20948_AGMT_t agmt); +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals); +void printScaledAGMT(ICM_20948_I2C *sensor); + + +void setup() +{ + + SERIAL_PORT.begin(115200); + + myWire.begin(); + + // Assign pins 13 & 11 to SERCOM functionality + pinPeripheral(11, PIO_SERCOM); + pinPeripheral(13, PIO_SERCOM); + + while (!SERIAL_PORT) + { + }; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println("Trying again..."); + delay(500); + } + else + { + initialized = true; + } + } +} + +void loop() +{ + + if (myICM.dataReady()) + { + myICM.getAGMT(); // The values are only updated when you call 'getAGMT' + // printRawAGMT( myICM.agmt ); // Uncomment this to see the raw values, taken directly from the agmt structure + printScaledAGMT(&myICM); // This function takes into account the scale settings from when the measurement was made to calculate the values with units + delay(30); + } + else + { + SERIAL_PORT.println("Waiting for data"); + delay(500); + } +} + +// Below here are some helper functions to print the data nicely! + +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ +#else +void printScaledAGMT(ICM_20948_I2C *sensor) +{ +#endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} diff --git a/lib/ICM-20948/examples/Arduino/Example2_Advanced/Example2_Advanced.ino b/lib/ICM-20948/examples/Arduino/Example2_Advanced/Example2_Advanced.ino new file mode 100644 index 0000000..8450c79 --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example2_Advanced/Example2_Advanced.ino @@ -0,0 +1,332 @@ +/**************************************************************** + * Example2_Advanced.ino + * ICM 20948 Arduino Library Demo + * Shows how to use granular configuration of the ICM 20948 + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define SPI_FREQ 5000000 // You can override the default SPI frequency +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); + while (!SERIAL_PORT) + { + }; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT, SPI_FREQ); // Here we are using the user-defined SPI_FREQ as the clock speed of the SPI bus +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println("Trying again..."); + delay(500); + } + else + { + initialized = true; + } + } + + // In this advanced example we'll cover how to do a more fine-grained setup of your sensor + SERIAL_PORT.println("Device connected!"); + + // Here we are doing a SW reset to make sure the device starts in a known state + myICM.swReset(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("Software Reset returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + delay(250); + + // Now wake the sensor up + myICM.sleep(false); + myICM.lowPower(false); + + // The next few configuration functions accept a bit-mask of sensors for which the settings should be applied. + + // Set Gyro and Accelerometer to a particular sample mode + // options: ICM_20948_Sample_Mode_Continuous + // ICM_20948_Sample_Mode_Cycled + myICM.setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Continuous); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setSampleMode returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Set full scale ranges for both acc and gyr + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + + myFSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + + myFSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + + myICM.setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setFullScale returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Set up Digital Low-Pass Filter configuration + ICM_20948_dlpcfg_t myDLPcfg; // Similar to FSS, this uses a configuration structure for the desired sensors + myDLPcfg.a = acc_d473bw_n499bw; // (ICM_20948_ACCEL_CONFIG_DLPCFG_e) + // acc_d246bw_n265bw - means 3db bandwidth is 246 hz and nyquist bandwidth is 265 hz + // acc_d111bw4_n136bw + // acc_d50bw4_n68bw8 + // acc_d23bw9_n34bw4 + // acc_d11bw5_n17bw + // acc_d5bw7_n8bw3 - means 3 db bandwidth is 5.7 hz and nyquist bandwidth is 8.3 hz + // acc_d473bw_n499bw + + myDLPcfg.g = gyr_d361bw4_n376bw5; // (ICM_20948_GYRO_CONFIG_1_DLPCFG_e) + // gyr_d196bw6_n229bw8 + // gyr_d151bw8_n187bw6 + // gyr_d119bw5_n154bw3 + // gyr_d51bw2_n73bw3 + // gyr_d23bw9_n35bw9 + // gyr_d11bw6_n17bw8 + // gyr_d5bw7_n8bw9 + // gyr_d361bw4_n376bw5 + + myICM.setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setDLPcfg returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Choose whether or not to use DLPF + // Here we're also showing another way to access the status values, and that it is OK to supply individual sensor masks to these functions + ICM_20948_Status_e accDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Acc, false); + ICM_20948_Status_e gyrDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Gyr, false); + SERIAL_PORT.print(F("Enable DLPF for Accelerometer returned: ")); + SERIAL_PORT.println(myICM.statusString(accDLPEnableStat)); + SERIAL_PORT.print(F("Enable DLPF for Gyroscope returned: ")); + SERIAL_PORT.println(myICM.statusString(gyrDLPEnableStat)); + + // Choose whether or not to start the magnetometer + myICM.startupMagnetometer(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("startupMagnetometer returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + SERIAL_PORT.println(); + SERIAL_PORT.println(F("Configuration complete!")); +} + +void loop() +{ + + if (myICM.dataReady()) + { + myICM.getAGMT(); // The values are only updated when you call 'getAGMT' + //printRawAGMT( myICM.agmt ); // Uncomment this to see the raw values, taken directly from the agmt structure + printScaledAGMT(&myICM); // This function takes into account the scale settings from when the measurement was made to calculate the values with units + delay(30); + } + else + { + SERIAL_PORT.println("Waiting for data"); + delay(500); + } +} + +// Below here are some helper functions to print the data nicely! + +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ +#else +void printScaledAGMT(ICM_20948_I2C *sensor) +{ +#endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} diff --git a/lib/ICM-20948/examples/Arduino/Example3_Interrupts/Example3_Interrupts.ino b/lib/ICM-20948/examples/Arduino/Example3_Interrupts/Example3_Interrupts.ino new file mode 100644 index 0000000..16e132e --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example3_Interrupts/Example3_Interrupts.ino @@ -0,0 +1,416 @@ +/**************************************************************** + * Example3_Interrupts.ino + * ICM 20948 Arduino Library Demo + * Builds on Example2_Advanced.ino to set up interrupts when data is ready + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: June 5 2019 + * + * For this example you must connect the interrupt pin "INT" on the breakout + * board to the pin specified by "INT_PIN" on your microcontroller. + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define INT_PIN 2 // Make sure to connect this pin on your uC to the "INT" pin on the ICM-20948 breakout +//#define LED_PIN 13 +#define LED_PIN LED_BUILTIN +#define BUFFER_SAMPLE_NUM 32 + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define SPI_FREQ 5000000 // You can override the default SPI frequency +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +// Some vars to control or respond to interrupts +volatile bool isrFired = false; +volatile bool sensorSleep = false; +volatile bool canToggle = false; + +void setup() +{ + + pinMode(INT_PIN, INPUT_PULLUP); // Using a pullup b/c ICM-20948 Breakout board has an onboard pullup as well and we don't want them to compete + attachInterrupt(digitalPinToInterrupt(INT_PIN), icmISR, FALLING); // Set up a falling interrupt + + pinMode(LED_PIN, OUTPUT); + digitalWrite(LED_PIN, !sensorSleep); + + SERIAL_PORT.begin(115200); + while (!SERIAL_PORT) + { + }; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT, SPI_FREQ); // Here we are using the user-defined SPI_FREQ as the clock speed of the SPI bus +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println("Trying again..."); + delay(500); + } + else + { + initialized = true; + } + } + + // In this advanced example we'll cover how to do a more fine-grained setup of your sensor + SERIAL_PORT.println("Device connected!"); + + // Here we are doing a SW reset to make sure the device starts in a known state + myICM.swReset(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("Software Reset returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + delay(250); + + // Now wake the sensor up + myICM.sleep(sensorSleep); + myICM.lowPower(false); + + // The next few configuration functions accept a bit-mask of sensors for which the settings should be applied. + + // Set Gyro and Accelerometer to a particular sample mode + // options: ICM_20948_Sample_Mode_Continuous + // ICM_20948_Sample_Mode_Cycled + myICM.setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled); + SERIAL_PORT.print(F("setSampleMode returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + ICM_20948_smplrt_t mySmplrt; + mySmplrt.g = 54; + myICM.setSampleRate(ICM_20948_Internal_Gyr, mySmplrt); + SERIAL_PORT.print(F("setSampleRate returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + // Set full scale ranges for both acc and gyr + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + + myFSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + + myFSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + + myICM.setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setFullScale returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Set up Digital Low-Pass Filter configuration + ICM_20948_dlpcfg_t myDLPcfg; // Similar to FSS, this uses a configuration structure for the desired sensors + myDLPcfg.a = acc_d473bw_n499bw; // (ICM_20948_ACCEL_CONFIG_DLPCFG_e) + // acc_d246bw_n265bw - means 3db bandwidth is 246 hz and nyquist bandwidth is 265 hz + // acc_d111bw4_n136bw + // acc_d50bw4_n68bw8 + // acc_d23bw9_n34bw4 + // acc_d11bw5_n17bw + // acc_d5bw7_n8bw3 - means 3 db bandwidth is 5.7 hz and nyquist bandwidth is 8.3 hz + // acc_d473bw_n499bw + + myDLPcfg.g = gyr_d361bw4_n376bw5; // (ICM_20948_GYRO_CONFIG_1_DLPCFG_e) + // gyr_d196bw6_n229bw8 + // gyr_d151bw8_n187bw6 + // gyr_d119bw5_n154bw3 + // gyr_d51bw2_n73bw3 + // gyr_d23bw9_n35bw9 + // gyr_d11bw6_n17bw8 + // gyr_d5bw7_n8bw9 + // gyr_d361bw4_n376bw5 + + myICM.setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setDLPcfg returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Choose whether or not to use DLPF + // Here we're also showing another way to access the status values, and that it is OK to supply individual sensor masks to these functions + ICM_20948_Status_e accDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Acc, true); + ICM_20948_Status_e gyrDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Gyr, true); + SERIAL_PORT.print(F("Enable DLPF for Accelerometer returned: ")); + SERIAL_PORT.println(myICM.statusString(accDLPEnableStat)); + SERIAL_PORT.print(F("Enable DLPF for Gyroscope returned: ")); + SERIAL_PORT.println(myICM.statusString(gyrDLPEnableStat)); + + // Choose whether or not to start the magnetometer + myICM.startupMagnetometer(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("startupMagnetometer returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Now we're going to set up interrupts. There are a lot of options, but for this test we're just configuring the interrupt pin and enabling interrupts to tell us when new data is ready + /* + ICM_20948_Status_e cfgIntActiveLow ( bool active_low ); + ICM_20948_Status_e cfgIntOpenDrain ( bool open_drain ); + ICM_20948_Status_e cfgIntLatch ( bool latching ); // If not latching then the interrupt is a 50 us pulse + + ICM_20948_Status_e cfgIntAnyReadToClear ( bool enabled ); // If enabled, *ANY* read will clear the INT_STATUS register. So if you have multiple interrupt sources enabled be sure to read INT_STATUS first + + ICM_20948_Status_e cfgFsyncActiveLow ( bool active_low ); + ICM_20948_Status_e cfgFsyncIntMode ( bool interrupt_mode ); // Can ue FSYNC as an interrupt input that sets the I2C Master Status register's PASS_THROUGH bit + + ICM_20948_Status_e intEnableI2C ( bool enable ); + ICM_20948_Status_e intEnableDMP ( bool enable ); + ICM_20948_Status_e intEnablePLL ( bool enable ); + ICM_20948_Status_e intEnableWOM ( bool enable ); + ICM_20948_Status_e intEnableWOF ( bool enable ); + ICM_20948_Status_e intEnableRawDataReady ( bool enable ); + ICM_20948_Status_e intEnableOverflowFIFO ( uint8_t bm_enable ); + ICM_20948_Status_e intEnableWatermarkFIFO ( uint8_t bm_enable ); + */ + myICM.cfgIntActiveLow(true); // Active low to be compatible with the breakout board's pullup resistor + myICM.cfgIntOpenDrain(false); // Push-pull, though open-drain would also work thanks to the pull-up resistors on the breakout + myICM.cfgIntLatch(true); // Latch the interrupt until cleared + SERIAL_PORT.print(F("cfgIntLatch returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + myICM.intEnableRawDataReady(true); // enable interrupts on raw data ready + SERIAL_PORT.print(F("intEnableRawDataReady returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + // // Note: weirdness with the Wake on Motion interrupt being always enabled..... + // uint8_t zero_0 = 0xFF; + // ICM_20948_execute_r( &myICM._device, AGB0_REG_INT_ENABLE, (uint8_t*)&zero_0, sizeof(uint8_t) ); + // SERIAL_PORT.print("INT_EN was: 0x"); SERIAL_PORT.println(zero_0, HEX); + // zero_0 = 0x00; + // ICM_20948_execute_w( &myICM._device, AGB0_REG_INT_ENABLE, (uint8_t*)&zero_0, sizeof(uint8_t) ); + + SERIAL_PORT.println(); + SERIAL_PORT.println(F("Configuration complete!")); +} + +void loop() +{ + if (isrFired) + { // If our isr flag is set then clear the interrupts on the ICM + isrFired = false; + myICM.getAGMT(); // get the A, G, M, and T readings + printScaledAGMT(&myICM); // This function takes into account the scale settings from when the measurement was made to calculate the values with units + //myICM.clearInterrupts(); // This would be efficient... but not compatible with Uno + } + + myICM.clearInterrupts(); // clear interrupts for next time - + // usually you'd do this only if an interrupt has occurred, however + // on the 328p I2C usage can block interrupts. This means that sometimes + // an interrupt is missed. When missed, if using an edge-based interrupt + // and only clearing interrupts when one was detected there will be no more + // edges to respond to, so no more interrupts will be detected. Here are + // some possible solutions: + // 1. use a level based interrupt + // 2. use the pulse-based interrupt in ICM settings (set cfgIntLatch to false) + // 3. use a microcontroller with nestable interrupts + // 4. clear the interrupts often + + if ((millis() % 1000) < 5) + { // This is a method to turn the sensor on and off once per second without using delays + if (canToggle) + { + sensorSleep = !sensorSleep; + myICM.sleep(sensorSleep); + digitalWrite(LED_PIN, !sensorSleep); + canToggle = false; + } + } + if ((millis() % 1000) > 500) + { + canToggle = true; + } +} + +void icmISR(void) +{ + isrFired = true; // Can't use I2C within ISR on 328p, so just set a flag to know that data is available +} + +// Below here are some helper functions to print the data nicely! +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ +#else +void printScaledAGMT(ICM_20948_I2C *sensor) +{ +#endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} diff --git a/lib/ICM-20948/examples/Arduino/Example4_WakeOnMotion/Example4_WakeOnMotion.ino b/lib/ICM-20948/examples/Arduino/Example4_WakeOnMotion/Example4_WakeOnMotion.ino new file mode 100644 index 0000000..79fb39c --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example4_WakeOnMotion/Example4_WakeOnMotion.ino @@ -0,0 +1,413 @@ +/**************************************************************** + * Example4_WakeOnMotion.ino + * ICM 20948 Arduino Library Demo + * Based on Example3_Interrupts.ino by Owen Lyke @ SparkFun Electronics + * Original Creation Date: Dec 5 2020 + * Created by mkrawcz1 (***** ***) + * + * For this example you must connect the interrupt pin "INT" on the breakout + * board to the pin specified by "INT_PIN" on your microcontroller. + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define INT_PIN 2 // Make sure to connect this pin on your uC to the "INT" pin on the ICM-20948 breakout +//#define LED_PIN 13 +#define LED_PIN LED_BUILTIN +#define BUFFER_SAMPLE_NUM 32 + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define SPI_FREQ 5000000 // You can override the default SPI frequency +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +// Some vars to control or respond to interrupts +volatile bool isrFired = false; +volatile bool sensorSleep = false; +volatile bool canToggle = false; +unsigned long lastTriggered; + +// Threshold LSBit is 4mg. Range is 0mg to 1020mg. +unsigned int WOM_threshold = 255; + +void setup() +{ + + pinMode(INT_PIN, INPUT_PULLUP); // Using a pullup b/c ICM-20948 Breakout board has an onboard pullup as well and we don't want them to compete + attachInterrupt(digitalPinToInterrupt(INT_PIN), icmISR, FALLING); // Set up a falling interrupt + + pinMode(LED_PIN, OUTPUT); + digitalWrite(LED_PIN, LOW); + + SERIAL_PORT.begin(115200); + while (!SERIAL_PORT) + { + }; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT, SPI_FREQ); // Here we are using the user-defined SPI_FREQ as the clock speed of the SPI bus +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println("Trying again..."); + delay(500); + } + else + { + initialized = true; + } + } + + // In this advanced example we'll cover how to do WakeOn Motion action using interrupts + SERIAL_PORT.println("Device connected!"); + + // Here we are doing a SW reset to make sure the device starts in a known state + myICM.swReset(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("Software Reset returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + delay(250); + + // Now wake the sensor up + myICM.sleep(sensorSleep); + myICM.lowPower(false); + + // The next few configuration functions accept a bit-mask of sensors for which the settings should be applied. + + // Set Gyro and Accelerometer to a particular sample mode + // options: ICM_20948_Sample_Mode_Continuous + // ICM_20948_Sample_Mode_Cycled + myICM.setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled); + SERIAL_PORT.print(F("setSampleMode returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + ICM_20948_smplrt_t mySmplrt; + mySmplrt.g = 54; + myICM.setSampleRate(ICM_20948_Internal_Gyr, mySmplrt); + SERIAL_PORT.print(F("setSampleRate returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + // Set full scale ranges for both acc and gyr + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + + myFSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + + myFSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + + myICM.setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setFullScale returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Set up Digital Low-Pass Filter configuration + ICM_20948_dlpcfg_t myDLPcfg; // Similar to FSS, this uses a configuration structure for the desired sensors + myDLPcfg.a = acc_d473bw_n499bw; // (ICM_20948_ACCEL_CONFIG_DLPCFG_e) + // acc_d246bw_n265bw - means 3db bandwidth is 246 hz and nyquist bandwidth is 265 hz + // acc_d111bw4_n136bw + // acc_d50bw4_n68bw8 + // acc_d23bw9_n34bw4 + // acc_d11bw5_n17bw + // acc_d5bw7_n8bw3 - means 3 db bandwidth is 5.7 hz and nyquist bandwidth is 8.3 hz + // acc_d473bw_n499bw + + myDLPcfg.g = gyr_d361bw4_n376bw5; // (ICM_20948_GYRO_CONFIG_1_DLPCFG_e) + // gyr_d196bw6_n229bw8 + // gyr_d151bw8_n187bw6 + // gyr_d119bw5_n154bw3 + // gyr_d51bw2_n73bw3 + // gyr_d23bw9_n35bw9 + // gyr_d11bw6_n17bw8 + // gyr_d5bw7_n8bw9 + // gyr_d361bw4_n376bw5 + + myICM.setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("setDLPcfg returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Choose whether or not to use DLPF + // Here we're also showing another way to access the status values, and that it is OK to supply individual sensor masks to these functions + ICM_20948_Status_e accDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Acc, true); + ICM_20948_Status_e gyrDLPEnableStat = myICM.enableDLPF(ICM_20948_Internal_Gyr, true); + SERIAL_PORT.print(F("Enable DLPF for Accelerometer returned: ")); + SERIAL_PORT.println(myICM.statusString(accDLPEnableStat)); + SERIAL_PORT.print(F("Enable DLPF for Gyroscope returned: ")); + SERIAL_PORT.println(myICM.statusString(gyrDLPEnableStat)); + + // Choose whether or not to start the magnetometer + myICM.startupMagnetometer(); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.print(F("startupMagnetometer returned: ")); + SERIAL_PORT.println(myICM.statusString()); + } + + // Now we're going to set up interrupts. There are a lot of options, but for this test we're just configuring the interrupt pin and enabling interrupts to tell us when new data is ready + /* + ICM_20948_Status_e cfgIntActiveLow ( bool active_low ); + ICM_20948_Status_e cfgIntOpenDrain ( bool open_drain ); + ICM_20948_Status_e cfgIntLatch ( bool latching ); // If not latching then the interrupt is a 50 us pulse + + ICM_20948_Status_e cfgIntAnyReadToClear ( bool enabled ); // If enabled, *ANY* read will clear the INT_STATUS register. So if you have multiple interrupt sources enabled be sure to read INT_STATUS first + + ICM_20948_Status_e cfgFsyncActiveLow ( bool active_low ); + ICM_20948_Status_e cfgFsyncIntMode ( bool interrupt_mode ); // Can ue FSYNC as an interrupt input that sets the I2C Master Status register's PASS_THROUGH bit + + ICM_20948_Status_e intEnableI2C ( bool enable ); + ICM_20948_Status_e intEnableDMP ( bool enable ); + ICM_20948_Status_e intEnablePLL ( bool enable ); + ICM_20948_Status_e intEnableWOM ( bool enable ); + ICM_20948_Status_e intEnableWOF ( bool enable ); + ICM_20948_Status_e intEnableRawDataReady ( bool enable ); + ICM_20948_Status_e intEnableOverflowFIFO ( uint8_t bm_enable ); + ICM_20948_Status_e intEnableWatermarkFIFO ( uint8_t bm_enable ); + */ + myICM.cfgIntActiveLow(true); // Active low to be compatible with the breakout board's pullup resistor + myICM.cfgIntOpenDrain(false); // Push-pull, though open-drain would also work thanks to the pull-up resistors on the breakout + myICM.cfgIntLatch(true); // Latch the interrupt until cleared + SERIAL_PORT.print(F("cfgIntLatch returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + myICM.WOMThreshold(WOM_threshold); // set WoM threshold + SERIAL_PORT.print(F("Set threshold returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + myICM.intEnableWOM(true); // enable interrupts on WakeOnMotion + SERIAL_PORT.print(F("intEnableWOM returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + myICM.WOMThreshold(WOM_threshold); // set WoM threshold - just in case... + SERIAL_PORT.print(F("Set threshold returned: ")); + SERIAL_PORT.println(myICM.statusString()); + + SERIAL_PORT.println(); + SERIAL_PORT.println(F("Configuration complete!")); +} + +void loop() +{ + if (isrFired) + { // If our isr flag is set then clear the interrupts on the ICM + isrFired = false; + myICM.getAGMT(); // get the A, G, M, and T readings + //printScaledAGMT( &myICM ); // This function takes into account the scale settings from when the measurement was made to calculate the values with units + SERIAL_PORT.println(F("Shock detected")); + digitalWrite(LED_PIN, HIGH); + lastTriggered = millis(); + delay(30); + myICM.clearInterrupts(); // This would be efficient... but not compatible with Uno + } + + myICM.clearInterrupts(); // clear interrupts for next time - + // usually you'd do this only if an interrupt has occurred, however + // on the 328p I2C usage can block interrupts. This means that sometimes + // an interrupt is missed. When missed, if using an edge-based interrupt + // and only clearing interrupts when one was detected there will be no more + // edges to respond to, so no more interrupts will be detected. Here are + // some possible solutions: + // 1. use a level based interrupt + // 2. use the pulse-based interrupt in ICM settings (set cfgIntLatch to false) + // 3. use a microcontroller with nestable interrupts + // 4. clear the interrupts often + + if (millis() - lastTriggered > 1000) // Turn the LED off after one second + digitalWrite(LED_PIN, LOW); +} + +void icmISR(void) +{ + isrFired = true; // Can't use I2C within ISR on 328p, so just set a flag to know that data is available +} + +// Below here are some helper functions to print the data nicely! +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +#ifdef USE_SPI +void printScaledAGMT(ICM_20948_SPI *sensor) +{ +#else +void printScaledAGMT(ICM_20948_I2C *sensor) +{ +#endif + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} diff --git a/lib/ICM-20948/examples/Arduino/Example5_DualSPITest/Example5_DualSPITest.ino b/lib/ICM-20948/examples/Arduino/Example5_DualSPITest/Example5_DualSPITest.ino new file mode 100644 index 0000000..dc1f7ba --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example5_DualSPITest/Example5_DualSPITest.ino @@ -0,0 +1,246 @@ +/**************************************************************** + * Example5_DualSPITest.ino + * ICM 20948 Arduino Library Demo + * Use the default configuration to stream 9-axis IMU data on two IMUs over SPI + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. +#define CS_PIN_1 2 // Which pin you connect CS to for Sensor 1 +#define CS_PIN_2 4 // Which pin you connect CS to for Sensor 2 + +ICM_20948_SPI myICM1; // Create an ICM_20948_SPI object +ICM_20948_SPI myICM2; // Create an ICM_20948_SPI object + +void setup() +{ + + SERIAL_PORT.begin(115200); + while (!SERIAL_PORT) + { + }; + + SPI_PORT.begin(); + + myICM1.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + myICM2.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + + myICM1.begin(CS_PIN_1, SPI_PORT); + + SERIAL_PORT.print(F("Initialization of sensor 1 returned: ")); + SERIAL_PORT.println(myICM1.statusString()); + if (myICM1.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println(F("Trying again...")); + delay(500); + } + else + { + initialized = true; + } + } + + initialized = false; + while (!initialized) + { + + myICM2.begin(CS_PIN_2, SPI_PORT); + + SERIAL_PORT.print(F("Initialization of sensor 2 returned: ")); + SERIAL_PORT.println(myICM1.statusString()); + if (myICM2.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println(F("Trying again...")); + delay(500); + } + else + { + initialized = true; + } + } +} + +bool dataSeen = false; + +void loop() +{ + + if (myICM1.dataReady()) + { + myICM1.getAGMT(); // The values are only updated when you call 'getAGMT' + SERIAL_PORT.print("Sensor 1: "); + //printRawAGMT( myICM1.agmt); + printScaledAGMT(&myICM1); + dataSeen = true; + } + if (myICM2.dataReady()) + { + myICM2.getAGMT(); // The values are only updated when you call 'getAGMT' + SERIAL_PORT.print("Sensor 2: "); + //printRawAGMT( myICM2.agmt ); + printScaledAGMT(&myICM2); + dataSeen = true; + } + if (dataSeen) + { + delay(30); + dataSeen = false; + } + else + { + SERIAL_PORT.println("Waiting for data"); + delay(500); + } +} + +// Below here are some helper functions to print the data nicely! + +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERIAL_PORT.print("-"); + } + else + { + SERIAL_PORT.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERIAL_PORT.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERIAL_PORT.print(-val, decimals); + } + else + { + SERIAL_PORT.print(val, decimals); + } +} + +void printScaledAGMT(ICM_20948_SPI *sensor) +{ + SERIAL_PORT.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERIAL_PORT.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERIAL_PORT.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERIAL_PORT.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERIAL_PORT.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} diff --git a/lib/ICM-20948/examples/Arduino/Example6_DMP_Quat9_Orientation/Example6_DMP_Quat9_Orientation.ino b/lib/ICM-20948/examples/Arduino/Example6_DMP_Quat9_Orientation/Example6_DMP_Quat9_Orientation.ino new file mode 100644 index 0000000..0aa1bef --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example6_DMP_Quat9_Orientation/Example6_DMP_Quat9_Orientation.ino @@ -0,0 +1,245 @@ +/**************************************************************** + * Example6_DMP_Quat9_Orientation.ino + * ICM 20948 Arduino Library Demo + * Initialize the DMP based on the TDK InvenSense ICM20948_eMD_nucleo_1.0 example-icm20948 + * Paul Clark, April 25th, 2021 + * Based on original code by: + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * ** This example is based on InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + * ** We are grateful to InvenSense for sharing this with us. + * + * ** Important note: by default the DMP functionality is disabled in the library + * ** as the DMP firmware takes up 14301 Bytes of program memory. + * ** To use the DMP, you will need to: + * ** Edit ICM_20948_C.h + * ** Uncomment line 29: #define ICM_20948_USE_DMP + * ** Save changes + * ** If you are using Windows, you can find ICM_20948_C.h in: + * ** Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ + +//#define QUAT_ANIMATION // Uncomment this line to output data in the correct format for ZaneL's Node.js Quaternion animation tool: https://github.com/ZaneL/quaternion_sensor_3d_nodejs + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); // Start the serial console +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("ICM-20948 Example")); +#endif + + delay(100); + +#ifndef QUAT_ANIMATION + while (SERIAL_PORT.available()) // Make sure the serial RX buffer is empty + SERIAL_PORT.read(); + + SERIAL_PORT.println(F("Press any key to continue...")); + + while (!SERIAL_PORT.available()) // Wait for the user to press a key (send any serial character) + ; +#endif + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + +#ifndef QUAT_ANIMATION + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial +#endif + + bool initialized = false; + while (!initialized) + { + + // Initialize the ICM-20948 + // If the DMP is enabled, .begin performs a minimal startup. We need to configure the sample mode etc. manually. +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + +#ifndef QUAT_ANIMATION + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); +#endif + if (myICM.status != ICM_20948_Stat_Ok) + { +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("Trying again...")); +#endif + delay(500); + } + else + { + initialized = true; + } + } + +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("Device connected!")); +#endif + + bool success = true; // Use success to show if the DMP configuration was successful + + // Initialize the DMP. initializeDMP is a weak function. You can overwrite it if you want to e.g. to change the sample rate + success &= (myICM.initializeDMP() == ICM_20948_Stat_Ok); + + // DMP sensor options are defined in ICM_20948_DMP.h + // INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) + // INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) + // INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) + // INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) + // INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) + // INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) + + // Enable the DMP orientation sensor + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_ORIENTATION) == ICM_20948_Stat_Ok); + + // Enable any additional sensors / features + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_GYROSCOPE) == ICM_20948_Stat_Ok); + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_ACCELEROMETER) == ICM_20948_Stat_Ok); + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED) == ICM_20948_Stat_Ok); + + // Configuring DMP to output data at multiple ODRs: + // DMP is capable of outputting multiple sensor data at different rates to FIFO. + // Setting value can be calculated as follows: + // Value = (DMP running rate / ODR ) - 1 + // E.g. For a 5Hz ODR rate when DMP is running at 55Hz, value = (55/5) - 1 = 10. + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Quat9, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, 0) == ICM_20948_Stat_Ok); // Set to the maximum + + // Enable the FIFO + success &= (myICM.enableFIFO() == ICM_20948_Stat_Ok); + + // Enable the DMP + success &= (myICM.enableDMP() == ICM_20948_Stat_Ok); + + // Reset DMP + success &= (myICM.resetDMP() == ICM_20948_Stat_Ok); + + // Reset FIFO + success &= (myICM.resetFIFO() == ICM_20948_Stat_Ok); + + // Check success + if (success) + { +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("DMP enabled!")); +#endif + } + else + { + SERIAL_PORT.println(F("Enable DMP failed!")); + SERIAL_PORT.println(F("Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + while (1) + ; // Do nothing more + } +} + +void loop() +{ + // Read any DMP data waiting in the FIFO + // Note: + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFONoDataAvail if no data is available. + // If data is available, readDMPdataFromFIFO will attempt to read _one_ frame of DMP data. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOIncompleteData if a frame was present but was incomplete + // readDMPdataFromFIFO will return ICM_20948_Stat_Ok if a valid frame was read. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOMoreDataAvail if a valid frame was read _and_ the FIFO contains more (unread) data. + icm_20948_DMP_data_t data; + myICM.readDMPdataFromFIFO(&data); + + if ((myICM.status == ICM_20948_Stat_Ok) || (myICM.status == ICM_20948_Stat_FIFOMoreDataAvail)) // Was valid data available? + { + //SERIAL_PORT.print(F("Received data! Header: 0x")); // Print the header in HEX so we can see what data is arriving in the FIFO + //if ( data.header < 0x1000) SERIAL_PORT.print( "0" ); // Pad the zeros + //if ( data.header < 0x100) SERIAL_PORT.print( "0" ); + //if ( data.header < 0x10) SERIAL_PORT.print( "0" ); + //SERIAL_PORT.println( data.header, HEX ); + + if ((data.header & DMP_header_bitmap_Quat9) > 0) // We have asked for orientation data so we should receive Quat9 + { + // Q0 value is computed from this equation: Q0^2 + Q1^2 + Q2^2 + Q3^2 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + + //SERIAL_PORT.printf("Quat9 data is: Q1:%ld Q2:%ld Q3:%ld Accuracy:%d\r\n", data.Quat9.Data.Q1, data.Quat9.Data.Q2, data.Quat9.Data.Q3, data.Quat9.Data.Accuracy); + + // Scale to +/- 1 + double q1 = ((double)data.Quat9.Data.Q1) / 1073741824.0; // Convert to double. Divide by 2^30 + double q2 = ((double)data.Quat9.Data.Q2) / 1073741824.0; // Convert to double. Divide by 2^30 + double q3 = ((double)data.Quat9.Data.Q3) / 1073741824.0; // Convert to double. Divide by 2^30 + double q0 = sqrt(1.0 - ((q1 * q1) + (q2 * q2) + (q3 * q3))); + +#ifndef QUAT_ANIMATION + SERIAL_PORT.print(F("Q1:")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(" Q2:")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(" Q3:")); + SERIAL_PORT.print(q3, 3); + SERIAL_PORT.print(F(" Accuracy:")); + SERIAL_PORT.println(data.Quat9.Data.Accuracy); +#else + // Output the Quaternion data in the format expected by ZaneL's Node.js Quaternion animation tool + SERIAL_PORT.print(F("{\"quat_w\":")); + SERIAL_PORT.print(q0, 3); + SERIAL_PORT.print(F(", \"quat_x\":")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(", \"quat_y\":")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(", \"quat_z\":")); + SERIAL_PORT.print(q3, 3); + SERIAL_PORT.println(F("}")); +#endif + } + } + + if (myICM.status != ICM_20948_Stat_FIFOMoreDataAvail) // If more data is available then we should read it right away - and not delay + { + delay(10); + } +} diff --git a/lib/ICM-20948/examples/Arduino/Example7_DMP_Quat6_EulerAngles/Example7_DMP_Quat6_EulerAngles.ino b/lib/ICM-20948/examples/Arduino/Example7_DMP_Quat6_EulerAngles/Example7_DMP_Quat6_EulerAngles.ino new file mode 100644 index 0000000..f5daa1a --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example7_DMP_Quat6_EulerAngles/Example7_DMP_Quat6_EulerAngles.ino @@ -0,0 +1,274 @@ +/**************************************************************** + * Example7_DMP_Quat6_EulerAngles.ino + * ICM 20948 Arduino Library Demo + * Initialize the DMP based on the TDK InvenSense ICM20948_eMD_nucleo_1.0 example-icm20948 + * Paul Clark, April 25th, 2021 + * Based on original code by: + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * ** This example is based on InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + * ** We are grateful to InvenSense for sharing this with us. + * + * ** Important note: by default the DMP functionality is disabled in the library + * ** as the DMP firmware takes up 14301 Bytes of program memory. + * ** To use the DMP, you will need to: + * ** Edit ICM_20948_C.h + * ** Uncomment line 29: #define ICM_20948_USE_DMP + * ** Save changes + * ** If you are using Windows, you can find ICM_20948_C.h in: + * ** Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ + +//#define QUAT_ANIMATION // Uncomment this line to output data in the correct format for ZaneL's Node.js Quaternion animation tool: https://github.com/ZaneL/quaternion_sensor_3d_nodejs + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); // Start the serial console +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("ICM-20948 Example")); +#endif + + delay(100); + +#ifndef QUAT_ANIMATION + while (SERIAL_PORT.available()) // Make sure the serial RX buffer is empty + SERIAL_PORT.read(); + + SERIAL_PORT.println(F("Press any key to continue...")); + + while (!SERIAL_PORT.available()) // Wait for the user to press a key (send any serial character) + ; +#endif + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + +#ifndef QUAT_ANIMATION + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial +#endif + + bool initialized = false; + while (!initialized) + { + + // Initialize the ICM-20948 + // If the DMP is enabled, .begin performs a minimal startup. We need to configure the sample mode etc. manually. +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + +#ifndef QUAT_ANIMATION + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); +#endif + if (myICM.status != ICM_20948_Stat_Ok) + { +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("Trying again...")); +#endif + delay(500); + } + else + { + initialized = true; + } + } + +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("Device connected!")); +#endif + + bool success = true; // Use success to show if the DMP configuration was successful + + // Initialize the DMP. initializeDMP is a weak function. You can overwrite it if you want to e.g. to change the sample rate + success &= (myICM.initializeDMP() == ICM_20948_Stat_Ok); + + // DMP sensor options are defined in ICM_20948_DMP.h + // INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) + // INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) + // INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) + // INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) + // INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) + // INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) + + // Enable the DMP Game Rotation Vector sensor + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR) == ICM_20948_Stat_Ok); + + // Enable any additional sensors / features + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_GYROSCOPE) == ICM_20948_Stat_Ok); + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_ACCELEROMETER) == ICM_20948_Stat_Ok); + //success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED) == ICM_20948_Stat_Ok); + + // Configuring DMP to output data at multiple ODRs: + // DMP is capable of outputting multiple sensor data at different rates to FIFO. + // Setting value can be calculated as follows: + // Value = (DMP running rate / ODR ) - 1 + // E.g. For a 5Hz ODR rate when DMP is running at 55Hz, value = (55/5) - 1 = 10. + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 0) == ICM_20948_Stat_Ok); // Set to the maximum + //success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, 0) == ICM_20948_Stat_Ok); // Set to the maximum + + // Enable the FIFO + success &= (myICM.enableFIFO() == ICM_20948_Stat_Ok); + + // Enable the DMP + success &= (myICM.enableDMP() == ICM_20948_Stat_Ok); + + // Reset DMP + success &= (myICM.resetDMP() == ICM_20948_Stat_Ok); + + // Reset FIFO + success &= (myICM.resetFIFO() == ICM_20948_Stat_Ok); + + // Check success + if (success) + { +#ifndef QUAT_ANIMATION + SERIAL_PORT.println(F("DMP enabled!")); +#endif + } + else + { + SERIAL_PORT.println(F("Enable DMP failed!")); + SERIAL_PORT.println(F("Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + while (1) + ; // Do nothing more + } +} + +void loop() +{ + // Read any DMP data waiting in the FIFO + // Note: + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFONoDataAvail if no data is available. + // If data is available, readDMPdataFromFIFO will attempt to read _one_ frame of DMP data. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOIncompleteData if a frame was present but was incomplete + // readDMPdataFromFIFO will return ICM_20948_Stat_Ok if a valid frame was read. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOMoreDataAvail if a valid frame was read _and_ the FIFO contains more (unread) data. + icm_20948_DMP_data_t data; + myICM.readDMPdataFromFIFO(&data); + + if ((myICM.status == ICM_20948_Stat_Ok) || (myICM.status == ICM_20948_Stat_FIFOMoreDataAvail)) // Was valid data available? + { + //SERIAL_PORT.print(F("Received data! Header: 0x")); // Print the header in HEX so we can see what data is arriving in the FIFO + //if ( data.header < 0x1000) SERIAL_PORT.print( "0" ); // Pad the zeros + //if ( data.header < 0x100) SERIAL_PORT.print( "0" ); + //if ( data.header < 0x10) SERIAL_PORT.print( "0" ); + //SERIAL_PORT.println( data.header, HEX ); + + if ((data.header & DMP_header_bitmap_Quat6) > 0) // We have asked for GRV data so we should receive Quat6 + { + // Q0 value is computed from this equation: Q0^2 + Q1^2 + Q2^2 + Q3^2 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + + //SERIAL_PORT.printf("Quat6 data is: Q1:%ld Q2:%ld Q3:%ld\r\n", data.Quat6.Data.Q1, data.Quat6.Data.Q2, data.Quat6.Data.Q3); + + // Scale to +/- 1 + double q1 = ((double)data.Quat6.Data.Q1) / 1073741824.0; // Convert to double. Divide by 2^30 + double q2 = ((double)data.Quat6.Data.Q2) / 1073741824.0; // Convert to double. Divide by 2^30 + double q3 = ((double)data.Quat6.Data.Q3) / 1073741824.0; // Convert to double. Divide by 2^30 + + /* + SERIAL_PORT.print(F("Q1:")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(" Q2:")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(" Q3:")); + SERIAL_PORT.println(q3, 3); +*/ + + // Convert the quaternions to Euler angles (roll, pitch, yaw) + // https://en.wikipedia.org/w/index.php?title=Conversion_between_quaternions_and_Euler_angles§ion=8#Source_code_2 + + double q0 = sqrt(1.0 - ((q1 * q1) + (q2 * q2) + (q3 * q3))); + + double q2sqr = q2 * q2; + + // roll (x-axis rotation) + double t0 = +2.0 * (q0 * q1 + q2 * q3); + double t1 = +1.0 - 2.0 * (q1 * q1 + q2sqr); + double roll = atan2(t0, t1) * 180.0 / PI; + + // pitch (y-axis rotation) + double t2 = +2.0 * (q0 * q2 - q3 * q1); + t2 = t2 > 1.0 ? 1.0 : t2; + t2 = t2 < -1.0 ? -1.0 : t2; + double pitch = asin(t2) * 180.0 / PI; + + // yaw (z-axis rotation) + double t3 = +2.0 * (q0 * q3 + q1 * q2); + double t4 = +1.0 - 2.0 * (q2sqr + q3 * q3); + double yaw = atan2(t3, t4) * 180.0 / PI; + +#ifndef QUAT_ANIMATION + SERIAL_PORT.print(F("Roll:")); + SERIAL_PORT.print(roll, 1); + SERIAL_PORT.print(F(" Pitch:")); + SERIAL_PORT.print(pitch, 1); + SERIAL_PORT.print(F(" Yaw:")); + SERIAL_PORT.println(yaw, 1); +#else + // Output the Quaternion data in the format expected by ZaneL's Node.js Quaternion animation tool + SERIAL_PORT.print(F("{\"quat_w\":")); + SERIAL_PORT.print(q0, 3); + SERIAL_PORT.print(F(", \"quat_x\":")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(", \"quat_y\":")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(", \"quat_z\":")); + SERIAL_PORT.print(q3, 3); + SERIAL_PORT.println(F("}")); +#endif + } + } + + if (myICM.status != ICM_20948_Stat_FIFOMoreDataAvail) // If more data is available then we should read it right away - and not delay + { + delay(10); + } +} diff --git a/lib/ICM-20948/examples/Arduino/Example8_DMP_RawAccel/Example8_DMP_RawAccel.ino b/lib/ICM-20948/examples/Arduino/Example8_DMP_RawAccel/Example8_DMP_RawAccel.ino new file mode 100644 index 0000000..b2d1819 --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example8_DMP_RawAccel/Example8_DMP_RawAccel.ino @@ -0,0 +1,196 @@ +/**************************************************************** + * Example8_DMP_RawAccel.ino + * ICM 20948 Arduino Library Demo + * Initialize the DMP based on the TDK InvenSense ICM20948_eMD_nucleo_1.0 example-icm20948 + * Paul Clark, April 25th, 2021 + * Based on original code by: + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * ** This example is based on InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + * ** We are grateful to InvenSense for sharing this with us. + * + * ** Important note: by default the DMP functionality is disabled in the library + * ** as the DMP firmware takes up 14301 Bytes of program memory. + * ** To use the DMP, you will need to: + * ** Edit ICM_20948_C.h + * ** Uncomment line 29: #define ICM_20948_USE_DMP + * ** Save changes + * ** If you are using Windows, you can find ICM_20948_C.h in: + * ** Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); // Start the serial console + SERIAL_PORT.println(F("ICM-20948 Example")); + + delay(100); + + while (SERIAL_PORT.available()) // Make sure the serial RX buffer is empty + SERIAL_PORT.read(); + + SERIAL_PORT.println(F("Press any key to continue...")); + + while (!SERIAL_PORT.available()) // Wait for the user to press a key (send any serial character) + ; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + + // Initialize the ICM-20948 + // If the DMP is enabled, .begin performs a minimal startup. We need to configure the sample mode etc. manually. +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println(F("Trying again...")); + delay(500); + } + else + { + initialized = true; + } + } + + SERIAL_PORT.println(F("Device connected!")); + + bool success = true; // Use success to show if the DMP configuration was successful + + // Initialize the DMP. initializeDMP is a weak function. You can overwrite it if you want to e.g. to change the sample rate + success &= (myICM.initializeDMP() == ICM_20948_Stat_Ok); + + // DMP sensor options are defined in ICM_20948_DMP.h + // INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) + // INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) + // INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) + // INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) + // INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) + // INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) + + // Enable the DMP accelerometer + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_ACCELEROMETER) == ICM_20948_Stat_Ok); + + // Configuring DMP to output data at multiple ODRs: + // DMP is capable of outputting multiple sensor data at different rates to FIFO. + // Setting value can be calculated as follows: + // Value = (DMP running rate / ODR ) - 1 + // E.g. For a 5Hz ODR rate when DMP is running at 55Hz, value = (55/5) - 1 = 10. + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 0) == ICM_20948_Stat_Ok); // Set to the maximum + + // Enable the FIFO + success &= (myICM.enableFIFO() == ICM_20948_Stat_Ok); + + // Enable the DMP + success &= (myICM.enableDMP() == ICM_20948_Stat_Ok); + + // Reset DMP + success &= (myICM.resetDMP() == ICM_20948_Stat_Ok); + + // Reset FIFO + success &= (myICM.resetFIFO() == ICM_20948_Stat_Ok); + + // Check success + if (success) + { + SERIAL_PORT.println(F("DMP enabled!")); + } + else + { + SERIAL_PORT.println(F("Enable DMP failed!")); + SERIAL_PORT.println(F("Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + while (1) + ; // Do nothing more + } +} + +void loop() +{ + // Read any DMP data waiting in the FIFO + // Note: + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFONoDataAvail if no data is available. + // If data is available, readDMPdataFromFIFO will attempt to read _one_ frame of DMP data. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOIncompleteData if a frame was present but was incomplete + // readDMPdataFromFIFO will return ICM_20948_Stat_Ok if a valid frame was read. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOMoreDataAvail if a valid frame was read _and_ the FIFO contains more (unread) data. + icm_20948_DMP_data_t data; + myICM.readDMPdataFromFIFO(&data); + + if ((myICM.status == ICM_20948_Stat_Ok) || (myICM.status == ICM_20948_Stat_FIFOMoreDataAvail)) // Was valid data available? + { + //SERIAL_PORT.print(F("Received data! Header: 0x")); // Print the header in HEX so we can see what data is arriving in the FIFO + //if ( data.header < 0x1000) SERIAL_PORT.print( "0" ); // Pad the zeros + //if ( data.header < 0x100) SERIAL_PORT.print( "0" ); + //if ( data.header < 0x10) SERIAL_PORT.print( "0" ); + //SERIAL_PORT.println( data.header, HEX ); + + if ((data.header & DMP_header_bitmap_Accel) > 0) // Check the packet contains Accel data + { + float acc_x = (float)data.Raw_Accel.Data.X; // Extract the raw accelerometer data + float acc_y = (float)data.Raw_Accel.Data.Y; + float acc_z = (float)data.Raw_Accel.Data.Z; + + SERIAL_PORT.print(F("X:")); + SERIAL_PORT.print(acc_x); + SERIAL_PORT.print(F(" Y:")); + SERIAL_PORT.print(acc_y); + SERIAL_PORT.print(F(" Z:")); + SERIAL_PORT.println(acc_z); + } + } + + if (myICM.status != ICM_20948_Stat_FIFOMoreDataAvail) // If more data is available then we should read it right away - and not delay + { + delay(10); + } +} diff --git a/lib/ICM-20948/examples/Arduino/Example9_DMP_MultipleSensors/Example9_DMP_MultipleSensors.ino b/lib/ICM-20948/examples/Arduino/Example9_DMP_MultipleSensors/Example9_DMP_MultipleSensors.ino new file mode 100644 index 0000000..0debeae --- /dev/null +++ b/lib/ICM-20948/examples/Arduino/Example9_DMP_MultipleSensors/Example9_DMP_MultipleSensors.ino @@ -0,0 +1,255 @@ +/**************************************************************** + * Example9_DMP_MultipleSensors.ino + * ICM 20948 Arduino Library Demo + * Initialize the DMP based on the TDK InvenSense ICM20948_eMD_nucleo_1.0 example-icm20948 + * Paul Clark, April 25th, 2021 + * Based on original code by: + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * ** This example is based on InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + * ** We are grateful to InvenSense for sharing this with us. + * + * ** Important note: by default the DMP functionality is disabled in the library + * ** as the DMP firmware takes up 14301 Bytes of program memory. + * ** To use the DMP, you will need to: + * ** Edit ICM_20948_C.h + * ** Uncomment line 29: #define ICM_20948_USE_DMP + * ** Save changes + * ** If you are using Windows, you can find ICM_20948_C.h in: + * ** Documents\Arduino\libraries\SparkFun_ICM-20948_ArduinoLibrary\src\util + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +//#define USE_SPI // Uncomment this to use SPI + +#define SERIAL_PORT Serial + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN 2 // Which pin you connect CS to. Used only when "USE_SPI" is defined + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. \ + // On the SparkFun 9DoF IMU breakout the default is 1, and when \ + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI +ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else +ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif + +void setup() +{ + + SERIAL_PORT.begin(115200); // Start the serial console + SERIAL_PORT.println(F("ICM-20948 Example")); + + delay(100); + + while (SERIAL_PORT.available()) // Make sure the serial RX buffer is empty + SERIAL_PORT.read(); + + SERIAL_PORT.println(F("Press any key to continue...")); + + while (!SERIAL_PORT.available()) // Wait for the user to press a key (send any serial character) + ; + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + //myICM.enableDebugging(); // Uncomment this line to enable helpful debug messages on Serial + + bool initialized = false; + while (!initialized) + { + + // Initialize the ICM-20948 + // If the DMP is enabled, .begin performs a minimal startup. We need to configure the sample mode etc. manually. +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + + SERIAL_PORT.print(F("Initialization of the sensor returned: ")); + SERIAL_PORT.println(myICM.statusString()); + if (myICM.status != ICM_20948_Stat_Ok) + { + SERIAL_PORT.println(F("Trying again...")); + delay(500); + } + else + { + initialized = true; + } + } + + SERIAL_PORT.println(F("Device connected!")); + + bool success = true; // Use success to show if the DMP configuration was successful + + // Initialize the DMP. initializeDMP is a weak function. You can overwrite it if you want to e.g. to change the sample rate + success &= (myICM.initializeDMP() == ICM_20948_Stat_Ok); + + // DMP sensor options are defined in ICM_20948_DMP.h + // INV_ICM20948_SENSOR_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_RAW_ACCELEROMETER (16-bit accel) + // INV_ICM20948_SENSOR_RAW_GYROSCOPE (16-bit gyro + 32-bit calibrated gyro) + // INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED (16-bit compass) + // INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED (16-bit gyro) + // INV_ICM20948_SENSOR_STEP_DETECTOR (Pedometer Step Detector) + // INV_ICM20948_SENSOR_STEP_COUNTER (Pedometer Step Detector) + // INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ROTATION_VECTOR (32-bit 9-axis quaternion + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR (32-bit Geomag RV + heading accuracy) + // INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD (32-bit calibrated compass) + // INV_ICM20948_SENSOR_GRAVITY (32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_LINEAR_ACCELERATION (16-bit accel + 32-bit 6-axis quaternion) + // INV_ICM20948_SENSOR_ORIENTATION (32-bit 9-axis quaternion + heading accuracy) + + // Enable the DMP Game Rotation Vector sensor (Quat6) + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR) == ICM_20948_Stat_Ok); + + // Enable additional sensors / features + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_GYROSCOPE) == ICM_20948_Stat_Ok); + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_RAW_ACCELEROMETER) == ICM_20948_Stat_Ok); + success &= (myICM.enableDMPSensor(INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED) == ICM_20948_Stat_Ok); + + // Configuring DMP to output data at multiple ODRs: + // DMP is capable of outputting multiple sensor data at different rates to FIFO. + // Setting value can be calculated as follows: + // Value = (DMP running rate / ODR ) - 1 + // E.g. For a 5Hz ODR rate when DMP is running at 55Hz, value = (55/5) - 1 = 10. + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Quat6, 10) == ICM_20948_Stat_Ok); // Set to 5Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Accel, 54) == ICM_20948_Stat_Ok); // Set to 1Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro, 54) == ICM_20948_Stat_Ok); // Set to 1Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Gyro_Calibr, 54) == ICM_20948_Stat_Ok); // Set to 1Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass, 54) == ICM_20948_Stat_Ok); // Set to 1Hz + success &= (myICM.setDMPODRrate(DMP_ODR_Reg_Cpass_Calibr, 54) == ICM_20948_Stat_Ok); // Set to 1Hz + + // Enable the FIFO + success &= (myICM.enableFIFO() == ICM_20948_Stat_Ok); + + // Enable the DMP + success &= (myICM.enableDMP() == ICM_20948_Stat_Ok); + + // Reset DMP + success &= (myICM.resetDMP() == ICM_20948_Stat_Ok); + + // Reset FIFO + success &= (myICM.resetFIFO() == ICM_20948_Stat_Ok); + + // Check success + if (success) + { + SERIAL_PORT.println(F("DMP enabled!")); + } + else + { + SERIAL_PORT.println(F("Enable DMP failed!")); + SERIAL_PORT.println(F("Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + while (1) + ; // Do nothing more + } +} + +void loop() +{ + // Read any DMP data waiting in the FIFO + // Note: + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFONoDataAvail if no data is available. + // If data is available, readDMPdataFromFIFO will attempt to read _one_ frame of DMP data. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOIncompleteData if a frame was present but was incomplete + // readDMPdataFromFIFO will return ICM_20948_Stat_Ok if a valid frame was read. + // readDMPdataFromFIFO will return ICM_20948_Stat_FIFOMoreDataAvail if a valid frame was read _and_ the FIFO contains more (unread) data. + icm_20948_DMP_data_t data; + myICM.readDMPdataFromFIFO(&data); + + if ((myICM.status == ICM_20948_Stat_Ok) || (myICM.status == ICM_20948_Stat_FIFOMoreDataAvail)) // Was valid data available? + { + //SERIAL_PORT.print(F("Received data! Header: 0x")); // Print the header in HEX so we can see what data is arriving in the FIFO + //if ( data.header < 0x1000) SERIAL_PORT.print( "0" ); // Pad the zeros + //if ( data.header < 0x100) SERIAL_PORT.print( "0" ); + //if ( data.header < 0x10) SERIAL_PORT.print( "0" ); + //SERIAL_PORT.println( data.header, HEX ); + + if ((data.header & DMP_header_bitmap_Quat6) > 0) // Check for orientation data (Quat9) + { + // Q0 value is computed from this equation: Q0^2 + Q1^2 + Q2^2 + Q3^2 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + + //SERIAL_PORT.printf("Quat6 data is: Q1:%ld Q2:%ld Q3:%ld\r\n", data.Quat6.Data.Q1, data.Quat6.Data.Q2, data.Quat6.Data.Q3); + + // Scale to +/- 1 + double q1 = ((double)data.Quat6.Data.Q1) / 1073741824.0; // Convert to double. Divide by 2^30 + double q2 = ((double)data.Quat6.Data.Q2) / 1073741824.0; // Convert to double. Divide by 2^30 + double q3 = ((double)data.Quat6.Data.Q3) / 1073741824.0; // Convert to double. Divide by 2^30 + + SERIAL_PORT.print(F("Q1:")); + SERIAL_PORT.print(q1, 3); + SERIAL_PORT.print(F(" Q2:")); + SERIAL_PORT.print(q2, 3); + SERIAL_PORT.print(F(" Q3:")); + SERIAL_PORT.println(q3, 3); + } + + if ((data.header & DMP_header_bitmap_Accel) > 0) // Check for Accel + { + float acc_x = (float)data.Raw_Accel.Data.X; // Extract the raw accelerometer data + float acc_y = (float)data.Raw_Accel.Data.Y; + float acc_z = (float)data.Raw_Accel.Data.Z; + + SERIAL_PORT.print(F("Accel: X:")); + SERIAL_PORT.print(acc_x); + SERIAL_PORT.print(F(" Y:")); + SERIAL_PORT.print(acc_y); + SERIAL_PORT.print(F(" Z:")); + SERIAL_PORT.println(acc_z); + } + + if ((data.header & DMP_header_bitmap_Gyro) > 0) // Check for Gyro + { + float x = (float)data.Raw_Gyro.Data.X; // Extract the raw gyro data + float y = (float)data.Raw_Gyro.Data.Y; + float z = (float)data.Raw_Gyro.Data.Z; + + SERIAL_PORT.print(F("Gyro: X:")); + SERIAL_PORT.print(x); + SERIAL_PORT.print(F(" Y:")); + SERIAL_PORT.print(y); + SERIAL_PORT.print(F(" Z:")); + SERIAL_PORT.println(z); + } + + if ((data.header & DMP_header_bitmap_Compass) > 0) // Check for Compass + { + float x = (float)data.Compass.Data.X; // Extract the compass data + float y = (float)data.Compass.Data.Y; + float z = (float)data.Compass.Data.Z; + + SERIAL_PORT.print(F("Compass: X:")); + SERIAL_PORT.print(x); + SERIAL_PORT.print(F(" Y:")); + SERIAL_PORT.print(y); + SERIAL_PORT.print(F(" Z:")); + SERIAL_PORT.println(z); + } + } + + if (myICM.status != ICM_20948_Stat_FIFOMoreDataAvail) // If more data is available then we should read it right away - and not delay + { + delay(10); + } +} diff --git a/lib/ICM-20948/examples/PortableC/Example999_Portable/Example999_Portable.ino b/lib/ICM-20948/examples/PortableC/Example999_Portable/Example999_Portable.ino new file mode 100644 index 0000000..ad58aa3 --- /dev/null +++ b/lib/ICM-20948/examples/PortableC/Example999_Portable/Example999_Portable.ino @@ -0,0 +1,339 @@ +/**************************************************************** + * Example999_Portable.ino + * ICM 20948 Arduino Library Demo + * Uses underlying portable C skeleton with user-defined read/write functions + * Owen Lyke @ SparkFun Electronics + * Original Creation Date: April 17 2019 + * + * Please see License.md for the license information. + * + * Distributed as-is; no warranty is given. + ***************************************************************/ +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +#define SERIAL_PORT Serial + +//#define USE_SPI // uncomment to use SPI instead + +#ifdef USE_SPI + #define SPI_PORT SPI + #define CS_PIN 2 + #define SPI_CLK 1000000 + SPISettings mySettings(SPI_CLK, MSBFIRST, SPI_MODE3); +#else + #define WIRE_PORT Wire + #define I2C_ADDR ICM_20948_I2C_ADDR_AD1 +#endif + +// These are the interface functions that you would define for your system. They can use either I2C or SPI, +// or really **any** protocol as long as it successfully reads / writes the desired data into the ICM in the end +#ifdef USE_SPI + ICM_20948_Status_e my_write_spi(uint8_t reg, uint8_t *data, uint32_t len, void *user); + ICM_20948_Status_e my_read_spi(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +#else + ICM_20948_Status_e my_write_i2c(uint8_t reg, uint8_t *data, uint32_t len, void *user); + ICM_20948_Status_e my_read_i2c(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +#endif + +// You declare a "Serial Interface" (serif) type and give it the pointers to your interface functions +#ifdef USE_SPI +const ICM_20948_Serif_t mySerif = { + my_write_spi, // write + my_read_spi, // read + NULL, // this pointer is passed into your functions when they are called. +}; +#else +const ICM_20948_Serif_t mySerif = { + my_write_i2c, // write + my_read_i2c, // read + NULL, +}; +#endif + +// Now declare the structure that represents the ICM. +ICM_20948_Device_t myICM; + +void setup() +{ + + // Perform platform initialization + Serial.begin(115200); + +#ifdef USE_SPI + SPI_PORT.begin(); + pinMode(CS_PIN, OUTPUT); + digitalWrite(CS_PIN, HIGH); + // Aha! The SPI initialization monster bytes again! Let's send one byte out to 'set' the pins into a good starting state + SPI_PORT.beginTransaction(mySettings); + SPI_PORT.transfer(0x00); + SPI_PORT.endTransaction(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + // Initialize myICM + ICM_20948_init_struct(&myICM); + + // Link the serif + ICM_20948_link_serif(&myICM, &mySerif); + + while (ICM_20948_check_id(&myICM) != ICM_20948_Stat_Ok) + { + Serial.println("whoami does not match. Halting..."); + delay(1000); + } + + ICM_20948_Status_e stat = ICM_20948_Stat_Err; + uint8_t whoami = 0x00; + while ((stat != ICM_20948_Stat_Ok) || (whoami != ICM_20948_WHOAMI)) + { + whoami = 0x00; + stat = ICM_20948_get_who_am_i(&myICM, &whoami); + Serial.print("whoami does not match (0x"); + Serial.print(whoami, HEX); + Serial.print("). Halting..."); + Serial.println(); + delay(1000); + } + + // Here we are doing a SW reset to make sure the device starts in a known state + ICM_20948_sw_reset(&myICM); + delay(250); + + // Set Gyro and Accelerometer to a particular sample mode + ICM_20948_set_sample_mode(&myICM, (ICM_20948_InternalSensorID_bm)(ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Continuous); // optiona: ICM_20948_Sample_Mode_Continuous. ICM_20948_Sample_Mode_Cycled + + // Set full scale ranges for both acc and gyr + ICM_20948_fss_t myfss; + myfss.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + myfss.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + ICM_20948_set_full_scale(&myICM, (ICM_20948_InternalSensorID_bm)(ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myfss); + + // Set up DLPF configuration + ICM_20948_dlpcfg_t myDLPcfg; + myDLPcfg.a = acc_d473bw_n499bw; + myDLPcfg.g = gyr_d361bw4_n376bw5; + ICM_20948_set_dlpf_cfg(&myICM, (ICM_20948_InternalSensorID_bm)(ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myDLPcfg); + + // Choose whether or not to use DLPF + ICM_20948_enable_dlpf(&myICM, ICM_20948_Internal_Acc, false); + ICM_20948_enable_dlpf(&myICM, ICM_20948_Internal_Gyr, false); + + // Now wake the sensor up + ICM_20948_sleep(&myICM, false); + ICM_20948_low_power(&myICM, false); +} + +void loop() +{ + delay(1000); + + ICM_20948_AGMT_t agmt = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0}}; + if (ICM_20948_get_agmt(&myICM, &agmt) == ICM_20948_Stat_Ok) + { + printRawAGMT(agmt); + } + else + { + Serial.println("Uh oh"); + } +} + +/////////////////////////////////////////////////////////////// +/* Here's where you actually define your interface functions */ +/////////////////////////////////////////////////////////////// + +#ifdef USE_SPI +ICM_20948_Status_e my_write_spi(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + SPI_PORT.beginTransaction(mySettings); + digitalWrite(CS_PIN, LOW); + delayMicroseconds(5); + SPI_PORT.transfer(((reg & 0x7F) | 0x00)); + for (uint32_t indi = 0; indi < len; indi++) + { + SPI_PORT.transfer(*(data + indi)); + } + delayMicroseconds(5); + digitalWrite(CS_PIN, HIGH); + SPI_PORT.endTransaction(); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e my_read_spi(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + SPI_PORT.beginTransaction(mySettings); + digitalWrite(CS_PIN, LOW); + delayMicroseconds(5); + SPI_PORT.transfer(((reg & 0x7F) | 0x80)); + for (uint32_t indi = 0; indi < len; indi++) + { + *(buff + indi) = SPI_PORT.transfer(0x00); + } + delayMicroseconds(5); + digitalWrite(CS_PIN, HIGH); + SPI_PORT.endTransaction(); + + return ICM_20948_Stat_Ok; +} + +#else + +ICM_20948_Status_e my_write_i2c(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + WIRE_PORT.beginTransmission(I2C_ADDR); + WIRE_PORT.write(reg); + WIRE_PORT.write(data, len); + WIRE_PORT.endTransmission(); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e my_read_i2c(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + WIRE_PORT.beginTransmission(I2C_ADDR); + WIRE_PORT.write(reg); + WIRE_PORT.endTransmission(false); // Send repeated start + + uint32_t num_received = WIRE_PORT.requestFrom(I2C_ADDR, len); + if (num_received == len) + { + for (uint32_t i = 0; i < len; i++) + { + buff[i] = WIRE_PORT.read(); + } + } + + return ICM_20948_Stat_Ok; +} + +#endif + +// Some helper functions + +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERIAL_PORT.print(" "); + if (val < 10000) + { + SERIAL_PORT.print("0"); + } + if (val < 1000) + { + SERIAL_PORT.print("0"); + } + if (val < 100) + { + SERIAL_PORT.print("0"); + } + if (val < 10) + { + SERIAL_PORT.print("0"); + } + } + else + { + SERIAL_PORT.print("-"); + if (abs(val) < 10000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 1000) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 100) + { + SERIAL_PORT.print("0"); + } + if (abs(val) < 10) + { + SERIAL_PORT.print("0"); + } + } + SERIAL_PORT.print(abs(val)); +} + +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERIAL_PORT.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERIAL_PORT.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERIAL_PORT.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERIAL_PORT.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERIAL_PORT.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERIAL_PORT.print(" ]"); + SERIAL_PORT.println(); +} + +float getAccMG(int16_t raw, uint8_t fss) +{ + switch (fss) + { + case 0: + return (((float)raw) / 16.384); + break; + case 1: + return (((float)raw) / 8.192); + break; + case 2: + return (((float)raw) / 4.096); + break; + case 3: + return (((float)raw) / 2.048); + break; + default: + return 0; + break; + } +} + +float getGyrDPS(int16_t raw, uint8_t fss) +{ + switch (fss) + { + case 0: + return (((float)raw) / 131); + break; + case 1: + return (((float)raw) / 65.5); + break; + case 2: + return (((float)raw) / 32.8); + break; + case 3: + return (((float)raw) / 16.4); + break; + default: + return 0; + break; + } +} + +float getMagUT(int16_t raw) +{ + return (((float)raw) * 0.15); +} + +float getTmpC(int16_t raw) +{ + return (((float)raw) / 333.87); +} diff --git a/lib/ICM-20948/img/Contributing.JPG b/lib/ICM-20948/img/Contributing.JPG new file mode 100644 index 0000000000000000000000000000000000000000..6f943b9628f80f119128428a7abb8b1b21f42c95 GIT binary patch literal 58028 zcmeFZ2T+q=*Do4G=|zxURX{+RN>e~$14M-UL3)>7gebiPqV$f4fYPFLr34{>v_!gq zfV3b95JHg-2?zuT$;tnoZ@%-s-?`tJbI;73x!>IPA$!8WPM)>aUhB74+Yj{@bslj3 zk*>ZjfR2t1;7I!cP_cmffHQP-f4~0iqCZFf_r-AbEd4n~21dre2NN?ZGZPaF6C)!F zI|~ad8|`9b=HO&!^TM+Ni3|i2@U6I{;6E2-^PvXSvRC zU%Gym;ezo~#>+2wZoJC)$Ru&^O9!vXC_z%$$uEkTg^yoAP)O>Ew2bUk6;(C$o3}LX zKhV+Dd#L~DiK&^ng{76Xvx}>nyN9Qje?VYRa7buabWChqd_rQ8qzYb&_&00+7ia%_j79w)arWu{_k0FPL&2@05P) zXgPq<+p(ZrK>Q4Fz5;oU)I+=vB51ecVTn+tHqYvKA8}n$EPiU#4c+O8ns%8XJnoWM zvQpna3c2~*2+DyXs5gZN@?he7PN5lp3V4hkKGos*i|&6KklBw^K*wDwpb_N`N=E{z zfEc|&Dj-(4CL~(-gz=yT+DHY|72|$~7J|05=JJC2>nAI*NKO(JK;c7mf>=Y!H(`#n zPvtyBOhyj=K0>+e;q@WyBs*-d^G(6t=Ne`*jm_EUfPf2_+CB?0~`4$=yRS+xioGSUr1@ORJZJGT&XlC)(u zG*p+dHExYx#$9Y|G_Q5L=w_77w*y0S(KJoMgghFtpuN8cIqYULpRyxGW>c;b4n7ng z9{U!1YWdxlG>kG!m+dpY#29TQc7w!B%sEgz{RjasQUR}!B0rH=LgW@)f1)8e^TMaD zDh7jwj-UIa4qySRKNnohZuF_$7+`7AawB!&-TP1^S)La4IEp+(dsLeVa`DSV_5N+B zj+j(@x6n%RP+O&nTI|+O8!SeU%Nq2)#4(A1UW7%lRO7GcdqmmV1sJb-xw~0>$5~FPq!H06|p#m_%2l1q#z!MKLKPjAWVm77{4o$FUm{c{i zYPhYcSdI8p6n;bL5v2a%Xw{p`_oN=Uzc*M?;B(-PRHpQbH#BttnaMh&ba!I#H=qFA z7hz*~Z>0;Jt5%60GLm!qn#edE)T7!~DU!T*WnVMWnQRGcY?w+zIFRHRI}GpR(Xe7~ zjo(=WDxf=<+oL75zdqTzkzbAFp#M2<47cdO>Sju7G0QJ=`F8R6NIuBZ(>f}^+abPC zg9Muwc8DoFN4l$kE-&#=_C~k#eu8_|-*GfZ%$-17>tF+4ndGo-?w`j86iZ1l_jt_g zK$j0PM;$&VA$+R0paCoSuDmz(XG?{l$Yu@|KE5HlT`45Ls5h}nFm_Xqj zr@g1g;_5A8kpk;O_+L2Fh$|}&L{hRuD=`Bo0!TUlAQTvvDkB(fM@Ikl_K#KO?Lm;l@n?tnbe!R2@Z&r zP3(!fIEG_!!6II|fw0_O^Q8u&3SzgR0^Hi8+ng*f7~gDBmr1i3I&uzvl92I`_s~AJ zvS)#vdziv@#9u4b9ZK1#czP^EP$J2|zoB@@!89}SA>Si##s;9a9QZa0h3vF@ySA=% ztc;wXGJj;CRZq&Z9dB;f;|M#CVE0JSkJEP2S%L25*p3^%>|fBT=7NHZXT`D*B?XUO z8_XKsBp=nlClxJ^{X>i2yvdQ0H3)*Ke_n1Z5N>PtS%Oqj0p}PRy0APhhI!$ zLVkbC;Tuu`Nhrx(uE|u)6hn!yvVE}^z7-iB9I|3K`uf_pdB>y$Al@4C>@*wbo1TnR zA>?!#N-u1u6C(|^e~(yeOE-*ex2Yd^n>MKhUk+46W8Z#fV_9-p7EBj~k-2dP5K<fqW3);ud2U zC;Lj07K@gIPq`&4|9fu#@>xc81Nn#DaG2z)gQZu896Mybu|d-blpE*_b~QNrIH&>G z!^ztBH24K`uCRA>#l_TFx^t5@XDcKwa%EULAYidjj~y)Tn+Zg4io)Z8W7U#?+jcM} zlb=!n%z=&7yvs3um4h64V4=jr;q!ngS-u`8Ch3f9@q$hxzTXF_iayo-`qM{VSex~u zK-Y=oCrPlb?|HOsl;>b0LcRs6mhgvF3FFYC(MRU(G9dYTS8bDmD{9EPo&@>n`aTdCBnB# z&@M*;Am-N$JQK+V@g+jZy#5q^P&enfwMZU90j{%OOWobuv&sh7Uor#r($m1qXw-VT zyI4uNrvattuQH2#a@#0c8!+9fGXq0UlJJqoH?0oqW-XuOG@G0>7@@b@-xRcZl}A?F zZElC=yh1ID0-JEBX;i>@;GcX8EbPl6ITzHqbHWn|CZ^CZSo`0)-WFjcA{T_ffJYIko)BE&Ev1RndcA>n)eRVPE3z zJ#t+qO)_?w%Qg9R(D|8_Eu|AT5`2ED2YiMyf{E{g$0O;8TG|&t=R^7ya*}*hPH)%5 z=Q<{7vND(2fDuENA8rb?=m@>xO*r>N^j+y$c6OjpH}}trP-e)h2tGk7{KhDEFsAqEkm>IZ>P@p zJs-!;S=ri3+^d(+zgqXu^oANe{r3T_&pdBi_WXnA%CBHb2}jm5b8CS$>t@eaKMrE? zSzagNQDC$C}f+ zEH)#7PZ4v>P6@g~G80uPU%4-8M(1==0kA9^Z?Gm65VRJq(%goftW%)^ntXRq9vGb0 z)Qaz%zNhn#04jha!`XWaI-l4Grl#SzFBIbt~_8fa2_f~v(;pj8~9hBG0{Cr6}$;Le;4kNZ9E&1EnM)$)+^}e+zl=dyliE*%s!RqAjRmm6bU(h#; z{wi||oprfYHS2<27ZniQM3EX()Y7RUP4(2nY&lUoaRJOJs;#-9U;X=G z+4zo04+baYn!5N}(&goR^hBU|llo@q!o~;&+zAzd(9c6zAWtU#*fA`2w(LX)ZoKmW zHdML1v%Rlc+Wno-^Ma=pg$7i;xi(V{w>eRoCM}v0wZBw(In?*PqOf7D*Xnf2K21IY z2d3UzOL{HxtM_Rf4iJ4Z6(nUe30QfP{dW5hu|ox9`e9CUelR@LXdS$d>o|%C8jM;nK=v#PSM-q$D`OcvW2>UiOBO~BghGV^hCi1)}%a-6k zeymqw17=;eT_w!QPA(!sC@bYm@cC;-8sne7eDRp5#dP~A=L-e;pTXXtg}VaAIy`{? zQp4V$h#X1`?oM2uXyctvRkt9-@PoWm6+jLefpewHk4A?S3Thj(?5~+csf=~}=9L7* zy7&%*QX|>pyZMg|LYlhdK70OU5E$+j`0!j$zOmz=WXASPLSBylHM(H7MU{ZB-r5`9pl zGowvUkZ{VZek8LJ$$!G5#&2bjKjsMrx% zHzFFnuL|)J^%^(+(lWZO5W8eSn32F5(Ah1Ry%sHH+50NuoR0=ZQB+Cl3%U(~Wu)L9 zq~KJ8ut0Wro}H#?)Vg;FR@iP-pzhQ64hhD~1qE9ZN~Oo5w|T#>0uhWa$!4nLF!$6p ziHiPGyZg>zjV(QGy~7KhY{vI5T4+j!(&?CYxCsCX<*auW_+FJ4JOI^r5DG4PRPS`> zWWaxw<~&W5>OT@BcVmRlHPt9*7#vfO`-ky1Vi6|}6k2wKFo|R#Ak$BqPot>-CR{Qi zoi`NcbYg+g?(nNW5{7hRfBRrj(!Tx;Ef!U1U<&fmsyIj0o0V>%-{~K1zDvp~7Ke*| zzLutzL9l%p)SI?4YL+-J6i)+IUajj3L(=-FF|yu=b#o0eoFT{GvqDG3`fY+}!KFYa zNms6i4^19&AtTp{u8zJ)n?enhpk&~!6Jpi+JKm5?@ZPhzqOV{Ph+i$CDM3s5sgr_g z_7p@Hq8{+mUNN9KwxDNp4gk()G8GsePrN(g>^_g``HGY$3yiio-$sO~2$jOHE=dNj zE?ZX&`(H9U3%Fr)PV`m_^c!kP+aerl({NN4#A6{q1t5aEevxHE;p*vH0xe>&=Z!hm ziRdk4zmGCtP2qZ_| z_(0Z-WM1ZPVg2tbrJBHvA9@x#&a0^N2u^O0CtpF0C;zTPkIKO(pHPu%e~}wZWdSTk z%W1l%PB+aRIhd<@| z4XA%CVYN#ud!3T>TNRf|VI?3di+-&~DiM$c5es(l51U#h9pmgQLRnz$=8mp2R(F1J z7_bFarAGr1xM=O$8--Hi5asH%dsN7ceNX`vgN#fhd>2;)gOh1=oFx^>#egPq#bbSP%$O7ryc z(Hm#?ye7?NY(Cq3ID2S%9Mo%s)q#9xs!g?e9m5#cV5iy5cxPMz+z{gYbxOnrGt?pg z^S+Q*YM6|Aee0-J(;Jo$b}l*Cc2hkJFe`R=mZO7Ttr<|MVhtblO1^4+p{ow@$ zWwXjhc0z_>RyG9h{R#0N$-`Du^(+-2Ovx4IG1p5aLq9@p5H?#-iK^AoUB{2vDiyX% zLq$v5TocULC1YeHUo(It(VPh=Pg)9ulR(L=^qRX(u+J&=UUePY@!fCrP}r9g7`!iW z(+V)td=)e&)*xs1a?7K}xfdlw7ABxW7Kq}>5akd0>eh)Pj#EueR~t%I#Y2fRnJHk3Q&9pdRDCg&AMnems}($FE#5Q9bO7%gaMrOm4S zRl;0@b`&=7W|itqUk4-LweAjqcO&1afN=2_?d*#Av+76BM14-7)&)|$gCX>b=}|~| z{ie=2B?2nZQm$FZyz(5LC6*pGTmQW50pobsO2wzhOJo;9e5YhRn3q)96)9k+gVDTS z>Ggb?wanH<`rY8yl$2M6#pr^9v2A{kb4gKK-#03t!9BLkV6ol1%et`ogNM*oTDw|e zx#yvE+vOdr-Gx~4uOgosKUcYi`w??(^MQO0LT#d-$oF8KY7}|GP+!v4T~CDN{zKuv zV$QJ{+!6jEV8SW)Gy0xk$&^{(nl}ZsJRz))IM#&hfH#`QjcvpW)^godO^DEFh zxHS%<8ESYw0#6i)_Y~~*=^O9_7jY_A7BvrvFEYlo=`6PHu&z;L2wR7Vi0&Kqo_xn| zZ{RR8S6TJXe8~VP=D*h7JxrI7n%BSMKuedWOAKPjy+UWtB-y zy!WVyowm?2Q_y!l&7-5XKTtH*8M|Ew;iUR5*@bD{rBPwimtKl$f;SWnL*tjuA$Mla z{;BY#Xpw|L#E8TAaw07D($t@?V(WX4GcB5I1|J%0^}czSyz_wRKHo(^`E8j!jz&tu zuML@+8;1vJr0_D5c|_1+Um;ucgNAmEXPB7W**Z*D0E1!cBL~MEkxl6!O;e=g=?5*w zc^r#p?lzpZ<*!+bHPVeY2oE{Uu^JF8o?jan=6(zZ%4+!=jU4aM*Az9krl&-5)stTN z;BP^m;J>$-g^Cw|i?z%D`$pZ*utVFZ-M-sC)!(v&aYH?E=O7ZK0z8a~6m2&iFy!3h z^u#Skz4jiz+nF7XbzB=bL+#Vdw=~4doz<#TVBaxc)$t?DhP7e;RCVs*V=jB$72{X; zlnppIcg{1P&$fLj8oFdIorLm$$IqP`MGWcL5T~LM5kMPrAC2`B>&B)yvZA_x-3&7g z6fj0NZhKD8eG4+RP$fn$2#}r-lDjEa`HGFjM8*^wjGsyEBFC3H$2M_s*j8WV=#&+P z&oq--iH5j)eil~Z4RKpo>>@BXw1%i!N=5KTS=zpwPWGJ|CZPVdD9T-*3p-7CipQo* z4gZtV3T+{eT=9c~m2MEdwI}LXgyxpNH~LG*!CSgQ_TPp`rzqyf+klj$_C-*-Jp&1R z){m6j8_Dz2Irrx8)O}I=xk(p&_0VUmU%&gLBMyK4TJ@aXWVF)p*9MZt=XYX-A_{Ox z5Gy>K-FjW#e9XtfG-_D02q39Db|dcQMPeblABEwxk`|MKMZN8XCmNufs~XGyXnR~e ztVgxoSlgum3$M77_Rw$KzP6Q6lIw9b9isTh0TmEW1zZUWe~*~x zu+2n4W^i_Z)#H--?nTF5&z@TlZD?#B6)=`F$9-sq%UOi(x>p)o_AMyI_ong{pSBiL z0q!FqDyua}tazqWf8O`=a@!ae<;WdJ%_j2K5#IZENwf1Kydl5$x`f=5+pbrTa*S{X z?N_GEqP#ckV&slqSMuAHy!2yW7A$EPWx&)|6xAs}B0f4;c{W|!uzrj_{_z_N%2JYW zLB3^l7I`3|NhcETwX~o{S*y?rBtGd9XRSgncF#%tglN)BJgi#}i!o0yw&Hy!D8NR4 z`Aj&!gYlis9p|v5<^7%1IW_|PRTUZZiPYL96dcze3UisPX|TNXrDcv)I!F1M?hKv8 z*(LfUkO0J=0O}gySi>Mui=3<;VMet)zwFnA5Payvk2zsSCYrI3Pcv$n86%H^pyeaA zDEx3)(lX^T#Df6qjHwg5OjL?T+}gJrEWcl|{uf5OXrpN{w@G3s8B*IiwS)HZ+eGukRFz7KSEP5Wj&VQ4A^ zBImPUsAF8M@;=am`*`)H6w5t_a0b94U`52VIzZ<(@ARax)rAl$;9ldG_U26MF%zs| z3!nO%hNY(pip+N|Wz@&KelJ01#5vsNcXcYEO|P7E|6c2)s`trlrN_02@J;kIy3d_6fdakzWImdI(QjxvxwdY_?97%MKd$zwZm|kbIR=@sQFH{T54U)YqPcys(?49AMCn;RUB=<#F z6vP{kEpXN&#>Y1JTp1t+oFrovteLmwo85FQ#UA)oUhAkzRtLa%? z&@dWt%DA<*=jShXfcmjsQDbn2bTse47h+&O^#>&s0y6oD;NJMOZr;+~hR%JVGqd1n zHlWw=Q2K>{NUovM!ApWz(>#=}U(#rFqs6SoqEh^n3BGbMvw#qgh&DJOh~P2snMwTWx8*@Wl(x zj6KTXkL%z0-GT+Mf*3DkX~NW@-)KYqtZ%!8DF|JGA#ZqZH)1G-?hZPBb0Vabd6+=R zHWko$te2vt@Hr&!5eGOR`L;Fl&SvK|y&HFGTnwuQ%AX6!(`}f^18Lz!ST!s`Q2`P@ z-yZ`g`DVgE|9q2qClNnfcHIQV4F7VPMAYt7z= z;BYWQi0_6+`_mA{lF0e8O%<;nNbl|%LXnL#`^)r(UeItxpHF~kluy@pQ?9*yVyRXW z@6Ca~%1+Tme0AFd~2JH$i?aj*sU`@QzO zwLb$r$Qz=M7R{TIhKXwYIG!rJXwaEy6J3TdbN4P3hEtDNkTo+kCFGl!&TSV023=TZ zrUEYLe+)9)t>gFq&QqHjEJEMk>&3@-eqrVNW*gFhaGHGFqac1`iVQ!JE7<293K3pZ ziqV!{Z>dg?Ycs>6&f`2xm;&V@l%K?H+uiPWWxdhc-RqZj?VCt(n9!QH(A#n&+pG(q z`k!A-QzqxP+oFqPieCP2je9p_Jw9-B&)qz71wB+Q)by;;vSIzF)ww?x4jeXxQNolMpf zS~S=J6(`;QmdjBZjvqPig-OdG-q`E8v9@RLdEczL?rTGH!oyzKOLZ5(U)feuD!cQ7 zMSPEuNfjg6w*5h55eLdI_}*?^SYOT*(Zu0x0n$GB=uzLnbD~{&UvsYBwF21EH` zAkmgTOl3}p(r+T26k_fFLTLTbXsGvvgdgwIu5mRs_Ut=gA~}VOD8kx2;|YMNdRyaNR z+L+3zHn!`~8rW40>e7f^;$(rk+Rj*Ebdz^QzU~zV4KUc2g-1o^7QH>)4nM7?tSJBq z(j<=jd=W|H(AM5EjtZdD`>xG-nym#|R61+Fc0AP7T`gxj1`)p!U)*1A@LG1=_Neb&&qDNv?f_OxV>-c^SmuI3Nq?_Y@eu3mUD zkLnWj?}UCSgy9YE4Q?Kjh0dZu-YdFTH<#!9VPA|&{98r#;WkBOo<^Caqb11I3W~vw zO01qxQn?Lnb*{Wc-2!Ip9;N`@;R35rb|k}$NA{dVeLE?%80x-G^JQH|drlE!(>h$) z;#)l7>c2+&g`Z|L4)<8@R?#96AQM@Spwwf{nNS7cUsMvX1bxJsJHu6g0vTHm7r&jE+iE&2%l$L?u2%~&samHWF}!vR6N?{QX(%hXonW%j+*q4&*3UWP*2ow@?B7@9pGI zY_=OvQeSqFu>`#yC~JcfOV4~dJLxxOP32T$VE4qj{pZSfjRN<&zF|%ASzj^rMyvAO zwER{-V$^Wut92>>&?Z++;_t(8SMA^C+h!GY?)LM}jjWJv3b*-Q*3<-2Fn#D|#Z}~p zT`*f~$Zgk6f^2Ucq87%*JO^YCTuSnpVpTU-g2_{#eykaL`KU* zo4oK1TkM0B55$#0(S~o*m6k)Vv5Df3&=&Dp%tav@dnRAURD9$feMQ$8{{E;?Q1bjX zc_muD^v;c2ls%V|v6$viXv>?uQ7Q4}QYEv)TVAE7zj5WtZOHw=rGhCK3=&R2wu^V; z=ty1qgg=yP4TNHx)NqE6KbRfU{zFbAIEV`H2*G+|tgwF^H8r_#Y8^w86$m~|Bpj0braSM3l zf?Qq+kJ-98U?)Vr4Wk0&9MZFpo&<}Swxb&IKMGysO6<@p6*(0 zYir&88q=9QR?m8am?&CiX|tTbv};+;RT(+raDi4wz;VqT-X{jY;Seotk-F&aC!|RJ zH>;0_8wq8(54?SOu}|L*vVE0g^F7f;qcw#s@o_3~0;ZBLiegRwx(1+s3D`0*-}_u( zVWzNyf~ivhl2kw?PRO%2-}9geKS0^&J08OUBS&#($U2LL!QDe2J(*QYcRGh`y41Wf zySVeF3zgaEtm1y&gS~qhEs|kN1#I!2$cH5N8hUfa{!zFp7osg@_(4lS()?gbNpvfQ zxHin6!IN>{U*OWCiy1AxE9*j~3rZZG6s4avf7-1(M@+|+7CaQI73Zzyn^WTiMFn_W zB`PEs>P+4~L(_~Xoz{_hg$iKbZ}+Ue(SvT!OOG%}Sx??AsS)%o%*NUh6E(4(M=4&UTHF>#{OOPUTUK)Vl+3~i*? zQc~rehA}4tgF%_nF>7Y&8~3ly4sxI7f^S>COG#}}n-vsRUW0N_E`(U%IdW9fW5~)h zcY$@1yioAlqAs@z~5HZvBz#v$4&UecSD)TLw==XsTlQ*7 z0EzcRg;d|s5+9F%a$z8kCo((y*46o*2*cUSM^vHbpk zQ9JMC5((5($eMO&I1vyLexDFm;Oy!CaXKW)PA$T`Z*Z>KH`7wHB>P3*G7~09{aoAF z=C^43DIM+LQ^@}Q)biL=u*qQo4z}nHHq?#)yMnVKrO2wJ;>D4)uqTbl3j!(;(tSbJ zoed?qJk~soTpDnUzT`SMc-iHq)cKbKAK%JEC|tl#r66F_JKZR@a#DC;U_~;!rz24Y zRjZ~^b$ET|-HP2fYgY5SVLs3e9y0}{9hO+7KRvwc(t5wz8}=uqpe=HPgWlE^lV(=F zxslelG@(l)BSch8NIbr#m9W?2z(O`CC24?otV7hhrZjjkR|;OJH8{mWLL zhtZ=c#4_~rJ;U8?;kSga^bVj%2&n5ItSlBU&Se$Sc(7rEsueOSE*bLts8?Z2+vKM) zF&4g`q}tNH^ebC~GwdWSOFB5H0IN~!N5yZC=4b%BG}MSZ+!!NQm*?}#^Y9JeqUy-N zkq8jo&o;ru2-bsS{xFC5Ks!0Z$v~zWvVqp2b>K*RplG83S4)H4igDbIEZd_}bM}nu z7qjQWXjK?70rWCykTBI9=9U~>W94C?j>g28XJY$Q>+J4)sagU_dX0W`cqhl-A#B_X z2NmV0B?eJYl|Ex#8_2jKq3+g^4_*xNQK_ zxQBh2B5CoZ2Hka`OqL~BF?@++Rz(>>an<-D900TAJ3kvZ8Q10n>(hF-djy!R~?Ff`4OX1UZaLHKY z$I&;;UN|^|A_X%gn-X~Jsi_lV}F%k=8pY#b}@IJ=1Il(pe`Ud z>#z_F=vht{61^E=sLEvS7gr@H@T_s4kC(!4R~u6gdf)teeoo!azp?wGJf??7Ge|TQ z5RgNe=`-@>V2{WNJf!taZ&e;QAcII<^B^%#qyWJ@7GJ<=75}iFFq7*uQ7CB0=3q5a zch<&}qx7A5f0iZcb^0Zb%nt%ysCv{Uu7+g4*!6~#({+IKiSP7L?+oTt$v$Mu@fZ`% zvyHp;mWU&1Lnr}vNAA~X? z1wt0*71HCB;7IW~(tEv2}=F`vi9a42RHv+^pZ0%3lKEIf0!mD?R^I=!T znIVGV^Hy54-Zz%UBj0WE!=?j}bH&kLAo_-)J_+0U+4oIfa|ND@+16kCinquNlz&mUBzD}gP7w?3#%!XXq#`NJ2lNI4R`+XCex#->Lj}s=cK8se? zZj4)8+g1{(Z)*WJX9hQbTu8yWkn)2}lF!1WvX0;~lGC`wUX9E3Oji{mwnXQ?DE7U% z*#HOK#n-~HM@4UfD6N(BnSQ?`s&`wVmD+c~)8&0gCJ>X?u^l{Vb0oe2$kTBO!+Rot zO*S^Tb?^%xErU;Tm?JkHGgpo`6$67 zv1osB9JAN=BO2vo*5M9DKQwho{5a6kOIkmG=sJ zF#0{kS3)VEaf@x?n(#A<<1T){uOl2Z9e;OKz zeX#gFZ(1eVJPRLwfvrWldqV)OW#%Q>b(bUS#`i0-Gq#CN2>-r;*n&o;dr-jFQp8NT=f$Q_-zOzY?gzJ~1dVxiV^fMlX z;>0VTs(yK3%(CG%p-_wk`XHmvzarGJDl*_DL#Cso;=*(09OFz3)Egz=h-^Q51j+{IMz{=j^=>D00M7SfWB8Vq)`Soq_R{!rfwt0qMP; z*umX|#%qAY8$nZ5l<_%6w3Y+SGi0~-ICk3D!9%&My@Q3W7v40gxR;fzXN5iopJ)Z1#uPU)`DOHj)AWr7Wib* zdt(&2?y)7pOv{A7=Dma_P^ct&(EF;Ka%YU-vB?eVl<#q6Yi1edDI4hyryG5*CxQEKTASY)}Mm=m|!? z&`Vvj=Om^_Qvpv4IPcVrDeOR8%R=nCKzT;Z9@6Yr@ALS7P^8@d4#;#n+@0>+_9@BT z^|>%F-VHvFA?vhG1fY0_)Du-+z*u1k5%lQ=kX+BvMyUc128vq`F8yk4i++$K%Impq)S3y|E75)?R9|&LxQ-<5W)m^5kC9cXK)e zyv%G`^_P#UR8)kSPPo9c?b36+0y>B{t-se4T@i0a5A2)5@&!_mswGQHlNhLbq`lFX z@IGD0EK%>kqLuWj9O4^w*k!I!PL|dvOF>s(j}9vL@dmq8iDaL>`Y=bpqE9M8TwUvM zD}qpO@}-W{{%PdHFWjoO43xoo8f!avzH!nm{>ko2l1>+|3H*$*#(C41^yj`E4}A6x zV^2?fraf3OZS88$HRs#|e2)=FGmui|w2kf!4uyCC$Z9Q5A)+VdTRokGLx zXJcAmrs{_=v9P`kXP`9LmFA ztu6qcPx>&HwFB= zuEFM9q309`>me99Ofo(9-dKB2=!7Au#a7??t&h=L{w{Y~AJvZ&0J@?0HXH=oLRtHX<~yAzF2&6nYbXl{pA|JE z5hb8z6e!TM;Emc`9>`itpizOlHP7xtn=uXc3Z4t9`WPWZ>a;0kj}Q<5Es1M^&+GkSn?HC?7;#P^f}y%Xp2@!LDb~6@Euy z?mIiRh-bgLkTX;D#uh0fUJFV?Ol9L17S`(FQsLHHe|CReJA!y@U6~w5kC-WX&rP*Y zh1-ptf95y&_QI2Q?IuHONKtL0tv4@a@3}@pXqkuuc(b%V+G~| z?C$qZv#2dRw*)9QoXt@zV)(DaF-r}gk{ZN6&v zvQMFN$Nv73)m@a4+K|uUu|buK0zbmW4KpM0k_ zcUnUfW1A}>xeI!>VHzUrzfd`HhUB-SGZCPviIqZ*Z!2=+_=C2zzF=ErUg5zw+3Dv! z27cvh>vD0~-Wq|@H#^nxTFpHn%Bfkop4MQvkI|?3;;UYHnd5Lfp{#wIS*3|1IPE6& zeF^hKXqTbWUe{00gT_eZskSGfWqI#t>5P~l%?*Pu+}!2fk6hndkqg%A46jTDh&}y8 zn3{J_q3}RL&}6GXeCEOsusiH`xzD-gw#KxTF115`2A$TIh@?2?UfgZy;?lFnp-E@; z|D5uUD_-n2c>m}+qG-`4$Y(Gd7u>#$PCE=95cIiOX@`4nbPUnADQalJ&{D=8khK%w z8jdTHcg=z?Tl*aG49Tri0SFokaNzRFeTW>FP~Lp+v+W~xS1PN$nWJbaFWyDs#mx0T zc03jZX}t!#R_M1TV453aj@`!kG|o;>#&vzZwq%HMAo1DjD{#{)Mqh_IlVm=e`PcZL zWWa(nTOl7dQUNG-T1|a)*&aF)4n85^$adC6FRvb1!1m^_6f!L_$FG+aN=s;Np?12U z#6YhkK;=Ko75m38nfieuSc8sqX~oNvSSnx*J&clrI*XH}^tx%MFYpnxvnUX$Dv~m2 z9C2!Hc=_RecwHf6`K_QHQ82OF|Gc{YlKp=<&B3Q{-KL#G zb0&Q}ktVaF$rr5 zAtL*e%9d~W?0x1CE+keE5F>bpLfr{(lMf|9sE> zm-_twR()t@^S5Kn*00*{mVq4feN*(NOke6(l^&zOSy;97K{XXXKDLI=KYjdrxLNtK(%ha42HIH0J@_>mT8F`XeNaxcKQTE*nbATL^y-^E zo?9pE@s8z3Q=gz6Zm4CN@5T+>7Ni2o4K!%=M3Op;^0>8|R@u~;g|4y3LVCQRVA@kj z;Lxh{RV_H>F3BG?Tk8!8@8xNmcm$^o~0Fn$;=>P@tsy$OYZ+dR3QZtbbpg$)BM(MMGpI)kkzpDms9Ygnb_A^cyX|X_mZZGtg z7Zorbkly+q1UC9l_E1uUEc{M^v`SDWQMBg}7=XwuV2ZllKk0h-*HnE;0E7PR&##ES zZ_61?#ye<+7DKZPnqsc})71ZPuYZ}vzaW7Iheqi=8ZN`Us=^G;-_GEffz?9irosQT zS%_nrsDQmSPa6Eu>PEfmk7Vjt>wy1^)dA3dg3wPgMc)-^=NJDOi2tK@Ctv(us`i^C z`KZnGf06Rf2LCUq{NKUgzohbCPb$1pJXYtXKkD$9@;xO%DR=%Gd+!<5WY?_=qhdus zks>uJ2uPK#2t-A?fS`g9AS#^@BGMrc73obtKtMpLA|+BIHPWR?Z=ojio=^iRp8MJ7 zjBy_Ke)s#G@BH}2_v87&&|87rYp%K0Y}dS|B6N2XM1LbT{}ABTqrP&+u1&N|dH#$29HiZT{n3nMIu67P*BWgsCEIK-6>{-#O z=zIYqCV(4wD!PU-<>OsPoBra9TK;_JfAvYUN-SFAExee-T+SGXch|Cd%s}5vW0KlX z95B64-bjrc@-wJ$qEKk_NSsBBAXn=nz3Y`Mlc!HTA*G;VrW-(~els9YudR6dulCAc zpd}H!c#yJfr%h_(a1KB26R&=-cyARH7{vFyymaimryk&Ar~GDk52I@TX83MTPm@^v z37&Z!R}1}y4Zr7XluH`yb>V-cTKw^C3{nOScn@#7Q5_0&A=HH2Zw7-zkJ)MB?ac$3 zp7W@&+u%dN`{;PU@fZAG?gVoJ>Tliz)_GlUV0~EB=y{ap(Jw#pm5hKgEtDV~L6xMK zwK(ECkD%|SpGu+abk^CHQ}~y?KmF8>hEA<_KBm(UGdN9=rvMRVc&_DFyTi z)sPSXM|79;(DB=ZA%A!0lq1_T<5r?g^w4_zCi)O4{Jridu(1UkXctnZgMdi=AXPCj zNm=dliDcVMEe{X1DwQ$|`SW!xDPx=A!k1)gPs}MVx)2zyzB=RrJ_q3cLwb@xEuE5T zei=ucQrIOu++bh2y@$(DIdSCLO^q?ENFchZ* zx>lgnTWe{a$71 zt@Oo70siea0B1oz^99SXq2O;I9fF&Roq5zR?Ex2WQO+qYc$V8yxyHe{MetX?_2k|` zmmQ9<_KxK-wXnW%Z#q z6Qrh!Y%h=mP+&Ea$X+H%#)BSu{Ks^n^^Vu;trk?3XV+q06%_i-eS0+3;dS6FqANFaSKjNmW!A}PWT7PyZqYbXn9gwasVS4p{^Vdiqs-VbHW~Y zqtpk?*UXySyu{jt?LHP97zr8at~Ky~`|!x_5(q@g#?E~9-Ct|L*U7Fzhyw9GUm@l| z9{qwNk4u%mzgN~cZ!QKBdY{K8wpO|%`D(47kn=h1%Wt~;7ajKJ4{&>wiqn2yx7JY! z>nN=HishgSI%$A@hPxoInUcy)2aT)GP(Yzg_=;AbpmdsLwZu!vNQLXP;~rA}e*ar! zSK&tvwzISEK$W0KH3g&*`7!~b$^vCZ-XdAjF>X2CaDs5$qE&f_PMt&4dR|-@%YsIt z!nPE{56O}r<~=yAF+UF?4v0R*;tsx-_fJ2d1au=XgxP}@bnIThijwIMa{xfM3}i1u z0bFLK%K6Vu81uw5q8*qEmVRkS<&k8C{>5p>eSK&6TyUSpB#zfB_5;)7i^h4bIMs*E zDB=TNY|!*M&%_`f;PCE-j+5&@|WQL zq~Ts7X`zC`r$G{F1fN#0gtWBw6=yW?bg$t!KTScZbwdZt%QkN@X_l&U$C|x7msX)t zJhF~xu?#r6U^>4`<H?T7jB1t!{Z)Q>qm9%brt>VV7Ls!ZTJ|-C#urozHCvmyzH66IMxtIe+}drjh9O%l z-40>&GY2ggDEct-TtP#A!Ozb7Bmk?%_FLN2#Utw~K&e56s_uz+x~bso|SQ z&<=`=^|a**cwBH@&AOf4sD~dLA8aUV%X0Q>$B|2_41U4DM|7vOQQ6P$T%J`zow?(W zz;CillH>KNN(QB(D$9=7hDW|}EF?s@N@3-hUj%;qHmgLxN+0)aYl^b!(E_nnNV+wH z#@Y*^qYj;4R#5g8i8`Dd(R#4c9K{zk+idFZKYhd49ohF(?JaO9=7IE1sHuq+^N2#v zxutCfPTxD<)6@+xY=-u1hzkiu?@lCduV{gu}D^qewcaNc`0UH{p1--y1CBem=9|1S04rEx#J(aV;X>%!vut{ z&|-3xfcqRsw1otdb7$KQ4PO=2b1%nHHL6IQpYdsTTd0p7>Xv@5?4KQ+O_o+`wMjhv zEJY@xEIU-E%bsr=%Zx=JLjS6SI)dNII85>N%1<97V;gXL=%Ocx^NrKakbsM@o*931j0ly_MvgZQ4e0DX>0R3dR%S`V^-^Mrl*C|mLK>60>X z=3M+~-Rxz^lX21_wd&%&tIc$-PV7Lb4<^mXC4~kpBRQgRaESIX;TMu$jmRH_< z9pA_W|LUat`CcNwy;0&=-*bvY*2@n7!8EVEJxKnJP?aC$rFS5Hx>@?-s16>M=4Ocq zHD`Upbw9qjotA3t>YojnkWcKVg$X_3nAl(wmrMJlXmgJv?Z9_xT9J@6E04X7Q=v(s zlBAXB@o2Zzw7*OY5(KR9I0@9OYN$g@k0NgBB@t{}%ZiqL)8pL;!4WzG@j7wrRcVOC z?(FwqTv2TWMOKd6U{m6n!V>l**a3Zx>O+g0AqV0&PvB6Edj1H{y#U_2;bs{fD` zsTF&3{mDD=)s!=GNM)=Y1^z{-&E9psB|hz|5g%)l&#}=n{e|mX^tYpHTUW!TBN^TjU2xh zN1kU%APz6^f3M%-#MP)%-SZGLT*UDUu{%&*(;^jZ^soY zzUK+|g5x?(1F$cLrfvM@ITpZ`O0Bu%BNQd?tmbzva9v(#>2hplq7Op&iYUjUqfZW^ z^BCA(z-ECaHo8);$_0uFKqdnDJh`%Ou8$6!BXK53<>gvAZX4K?orB_~vZ8)cbWh82 zaaXx`7dvYz81JQ6wn{-Z`dy~1R^at14x8B{t&Iu3?pJH6>n>pjlgoJzca+1)Ti|E` zMWR>JG?O>Dd3cKBdoR_GxcMMMSK0iRv^=JKz~nB5Wy9FkdldOI7XQ78^~1K>5n7pw zK5-k*+Jrvtt)(Bd=?)F9HmGow>YJNm)6 zK=~y_@c_t_ANq*Fck9+FDh{ka8qdGYF6zo?r?2M}C4SBH@~o(+tfb_IlcaHi1jDdh z)TkVk;q_Wgk@|2%s+JoF zp0u&VNAzp)4KK)f#v=-F<@KVRu(9XC?5|yrZSOO7+7dywMW*r>wc5b5B`E#&jwV(CIY$W&~W zA%gAxrsy^{AcmWuAd_In@U!7%Q;~qnlhw*8$BO+e?4Za8DxxCetT(TIgl_*%4=1eGX`Yd~QUWo7OPmcH6 zg?jMOu{JJUebKscDtjvBz10Ft;nR3{-H22gLWDgDjRi@1^^LFah|fg{?)@UC6?&`V zH=~ayy~-q_ni1R(2hM7r;N@L$CLI@>kS-r&A7A`=UjEPQn%ckUw^2=-p}>9D7)sQ7Lq8WV=o=jM7kQL&aDp(}+SbiJd%Qs*t;WHm z@L5#f5$(=fabItD%CrerERfOtQcySD>2OtV^%SFUim?%8z>CUSx`a+uV8uaOp=Gq_ zPw7%+#0@O$FTKBYcyIiHVF+#^3}MHEx2{%)c@y+Tf`zwZFU49tEqwj>n?Y$%TGFoFz)o32 zjjzv2372lOEBzRd4EXZrv9zT64?Q2t< zam-eE{T|S7&<~-UAo#>@V(ZzLa$V)f#`i!isXZ5_z2Kh>7ZJLLMv}8*7GYP z<~i>V(@M)r+mDWqxA5()-SM`y7S!1ijdXr~pgoVuz;~l)!d56>X>0;|dmc00Ra?K{ ze?$YBT1dS|+HYiKN4k?-K1`kS2RHHLrhS2NnwntPy1&Bv-M3Xdw?1_$2d!ZI5Jb1uL-$fjvWu zZMmh2rxDsM$JmT(>60s;RcSJmrnBkq#Ru>2?T=J&YkZQ&hhk0#FpXilD~|`3lyW; zH79|aWJv@8bbhol5XDfXH(fb8;b?T8F*?KXyrpQ$MVm)#U*2(Qyg2R5hU5oQNzz

j2HZqrvMeUKk)6R>b0gD-q2AFi=R6v-JA{M7{lP*O&HXXp#LyLM1C$uh>_I8}Eza zxrJjK$4-sTzIXe+c?=F6Q1KxNJ|PK5%@ip;A=;QvW`tZG@qoKf?pCKTy_WA`KiA}d z`8q>TlGPqze#3Q|(i3OBDUM#57@<@_mmF_=N6?U*l!LwvcGF+VO6wvdE<$<^-cqE= zWQw&Uf{dT&X$VD&(zv{~0C9lUN$y?I6&~VrqEE#F0 z6L-NwIrU?~=kOKI$0oet*BjGko1uIapf^03PHI8})LR5qhz{A!qZr^MSB8yFPF~#j ze12TKU80*$r0e*;9P=vn_11t9V)5`A05-^0IIuLID~FDFqqbnXTZf9_B!HH!hX85> zBBTAJsjDQVSI22PiSL%9p5gs<=bFUjxIaU*i?h=Y_KtkJ_gn;4Ci)nCg9vK%*PHcf z1_vqOnqL&>WRtU+eed^cC2dxnqpV8?XRN65F40- zoC8ZHn+z??EZuORs9f!9X1zAxY-&19p9b5d9n+0#ZC%0Fg8*`gw^@&E;Rb7^<_d+` zm8U89_nvZ$Z%z0X!^Y`gqz*~C5%k(ZuYDs1(Mq7=XmN&*Alkw zd2N-IEa;-L0bgn92t-;b0NV5Nqj{3_ZYe5W^-B0bMk}Zs)DjaioUWV>;4jWG6+nZN zOpK>`Sdu+>y@QAG&tqqU<=m&O6XorWOcrx$if?JMZveUIO0IB;010wTKmp&+PgM2yPd(n`@r^ZcE?FlZIlzuQU*XKUoX;S;WzAnAbL=Ppqpz+uy zW4jAxk-FK^cL?WN6r^~qNQGFJ{K^6;<`*y zT?qNI^3B}AVMO_HVdA^{!M7@npT_B!3p321Qx1MOM~#~rXxULv0H|K!(4*38Na~PU z@tZ;9Fnt}UGMxSICO-9MhKtLovjTl^TSrQP>N!B{v~%86EF%Ok^T%ufl35afO}78 z@JGEUx$`r*H_EDY_Ab50Wa zZO>BomhgZ^OKySJ^M$btzq|L@a*aM9f6QHQ2P(YxBRj?K$r;b3pb5ltDRX?l;<*`Zx5_X=0a@f;vwbguB}fXY40 z{q3f&5Ou!TwhPT`)@Rtvj^MI9H{4!BrbmI(w8I1BAF=0tGmzL(&!E2GVfqL|<-D*8eFME)skaH^))N!jtL)FU z#!sm|mghj8_e{@CEsIzULi9o{z{zqDvt(+7mZRFsy>?!g zgR*qkz`qy6S9r}ddL<6!tK%zF%@zkinZVIil{CnPk2mdgJ&)EWC!D)U{q@Q~Xf2>! zCUN7fhjU!Y&H2uWpC%2GovBqk z6AG-Bhn0+Q43Z`b{ZkI>8*eW$q$3gK3?~>krvH?S5iJPyo8eAD4~4|~o8i31)aqer zDJ3zmbo_9`=NE>ex|+eg14+9;Xw9GL;qvxKxs|Fd4`rQpP^wgN)kbqPds!Q&Xir}E zEVqKZdCB*ZS(+0#5o-198DSe?BY7~=$@Z^Q(1wM zEdH<`+s@xxf$`~5To&t~WQB1sog4QOi(N+jdsX_9BXF;LeBP#LU#N}^BE;`g4J;Y4 z4L__rOxFO)e+^0jXIJT*1LZo@t8M}bx!!Q(rOHa&Mi!iZDlW90Kc^?@1=i^v%luio zwV;gcvGvx zMs{H(eWm}95$Mks=Ezg2s@g2tMBSRAW8jA?Qjcak_A2U4bf*$^e6Nmf!%g?t$j=Iv zllEdhue{LmN9z!R{0z^nn8Z6)zptT=r(S#h-L%9}rClk)BozFC@_NE;+3GCOKjf8) zjD6N}*o#EPYo(V}2QkK#I#<)p%(7#{gc3a^bcEvcMgHx3T`R9LnVu`GpU?X=g-+f? z6E^7k1=|V^h3GZ$-wcP$R;cMv6gk{Eo#%VCWfD)(S|6zPwXtebZ^8qVIm1Cb{mcx( zkSxsFoWxg{q!^ty$nP={c)&A*nwdf!$ZlTv%`m#^0eCoy9Lrdu*$uW4`spkZ=Z(QD zn(`Ho`5Aa}(tMJrygdLHjU@p^;djCA1UJ@OVW=_rfM#KbwRQv^1OEpDvggkVelzIz ztMw620$vd-Ria|>6LBNKG5b!zbmv#g7Uvr4#Dxc$I*L2S_xbRF-w_$m1yM< zd|HHpv!rUAyTGEm7AP*Gqx@@eL5@bj_^G)G#mXIbcoDDXr9FlF4oV%@6$&OiyB=f= z=3KfyM?Q`>B}ak7lMK`OpA%6z2TJ=g=F^Hj5-NM0m)_W)-U^9R1ZJEP#m_YD-5|T= zE&1lARG;mC;xx?WXnaSlz(*Nkt`oJl*Dw#Z4aEm&t5h7AMj!Wr{;3=P>0W$zj2A-Y z!b8uu6&5WdElP(ztH2DN#Mwd1ua>gwy1=KCe>Ql6W#r@#8JQgjtwr{=dCsZu9YD*KCP|asB!-9_A+83J<(B zM#y+&q*TK5VRdaH>BNTvBNq*^lJ(QSCaZ2vk}zurc*9WT$>^LfV^+DJ^Tuh>w<7qB zHx1(;$i<%tpAydY*=I=UcgA_o0g=_e(?IqkT)_bX4pXe9gGJ>O_HgFs8?e=%leov} zX08h|EQSD$xEj=H+fr`tDEVO)nFR=1IO(84)7y0^Qv`8g(ur)+GONqF&`HDY24z%Y zmoAgsDGO3KV4eO@;QwR*uA!iwSz9;ICjx##S&_%SczbT^_W~m=8b?Na(}LDp^Srz~ z_e~!haB*>6&=c435N~-a{i0v-=uA`=$ByA>8@?^rp7^oaCCDSMb0!4qFQ5m1z9;+& zs%uvheYfnGigA0ejDEe!*LPV?vvq&k+$_o&z_AT9&DbY^=vRW{hk#-`Sdy`P6fXfx z^$Es#1tBkIs^jZY>|d4F)bZX8q1;`f1^2J8mh}kCN-ZmCY;C+NWBC-=Z9|r(pWY`% z{P1PT&l&U9o^Zrf1_G&z@?l(JfnRac+@+2!^OjIJS=z684i%E z&QIwirzKwOGa#tHGi#EO@WcMwE!$Re38;oGZPYKsTc&U%RQbZUoVxvSz7F0>>!&H4 zV-S}SxtqaaamU9qw9JrWGEQHrU8RD}9RKXy@n14Mne?Av zhM2WFiX!>pj~E{~O7XQ*yUHG*uJ#xon}mhW4nO%-v=zt;;4^v^|Czo2UnJzq7O?cM#dhW%k6)Mw=B?uoAxU+ujHW1UL@#+M@*Cizf zoL_ueQ#CZ!nTrFg1I#=;$Uw|u88*@KY*{S2GMKeP1bV?RGaL1bU)Oe3unid{ z8BGWv-i==l;M>Zn?Vr9UY_bQZ zBqA3FE@%wo4eX|_GJRNk&rsPTe?cg&?Z<(Q9e4YRzOO&K@&msd8sL1!q5L+w64~Cw zh`qsNZUNDX^}f{4_CYFB_Nv;c)Fv;J>k|%MoLUBnzwUpSn#fDER$1irUQOBVM2~vm z)22h@;n$Z;m$^a+anpuX5tf5j>M_BFSXNx3>#cj<0ub#73=9{K*4c%-y|tUjEuI2Q zST}9HBj~134*UB2GF@-OGE$m_D&LE|Or%SnS@yLoPQx!rns?mdwcVQ4{&22Crst;6 z$GJFzmu^q0Pp-|+^e}bK}4 zka`y^P{&xH?@y=(DQ13roK>0Xyt7_tI#DCoRUtjPjbF(75}c^a>k-X>{o$c4d(-j@7bpeN-8qM3ylFRB!h$^$3uwvSBGl#B@-`ZFO?$x z)Q-|}n_KVZs>QjULIpQp!b&o8@|B(Gk~e%h~!cK1pVy=Vp(>lKUg$&u3hX!pETv z(uuLr!{%Nx!AIZPUi&_Y@lQ&tU#;^Rn*0D}R^wjEI7#J&18pBHV<>w^PK0<9Vo^u2 zNhnG@tzS;2vqr#>`^Ri}fg91j$uxyELcU#oa@gvokInEb?kTt#z^|Pe{1YI5oLNH}mjny00teowYbaFt){4m3;#Uu}yw6C{7nRD?<)(({Xxz0zQ5KIiT=LFk zlVYiFo2uqkvGY)JAX#pE^Zn*!FMEeJL+Pd>sa5>k6lay*_&U!*`_6LQ7M-x*gLfBg zSd7KlUDe_3Ox!Q(5cSRDD&v7GT&-5wZ^$Sed82YnwJXIl8L8j;5qFoV+iLH?xiFQt zs3_6L0&>qY*O(z3Sw1^wVMs6>t7)_n?Nhn+OtQGhmMcgypeaW$7v_b7cNf(+t8--_ zL(=`#GQGCiOaC5=u2Q8j@Rt3(9rKRPkjw+}ZH60m| z?hdLWJ@0nq&q&*|d6)Ro%$ji%x#(t(Fd*{-v9@}j{HQ!us2?fC_h;9 zfYjWgIA%{TbVy%GaJe6M5a$zVBYbzwqC~jnP;~j(z2!Gep{ZTt+ya`$M_045@KMa(@-?;%fdtZ<;aN0irtA-&O? z#=}1*dM-cN`t<5M?xm)z+w!21KV)T}it47V>D`N421c6bZD^%?!}d&x;2?;ZcX`eD za;*l?O=Z2}wvtk}kf*wv*Ar?Jw_wKiWt)%1oB8$Y7Nv*4;pHt@_EoJd@s1MieHu61 z`5>_Q@FP#k9l?{{R=ZNiyJ9)dAThD;o$s?IxGt3&`EAk=fb9I64yk~mcb0T{qh>~e zRYblzDy7)PBAzJ*<+Nvxp5l(X1=A5w@_uuyEHPLvP6=7(bMs3E0C#+QL92IXJG13# zQiyzhxxU(I;lz8vza09nU4Ghy{L#*H6zV#Q7Ew)L2m6>q0T<>kL*VKnMVh9TtBe5g zQYrWqRYY>TC3huhGv86xL5aBlhB+)yeVeKWIp(2~YJH%|@!|yJ;)Gj4RzObxTVG}v zOR8)Bsq(OLz7<^1uiSwr-IwCDg@81^t?>_kTC*tbl$CfzW-9!DEo?L~6$L@XQIc$Y z{IP33GY~kVW8-vl_gS|)snMXp zEWo%N;gfDK9AkIHg+y)E!g7~iYR#&ujcX?9TE3(-b614?dcHk9_0>>5df*%PD6%hOljnao5 zAnwNF-KtHU@GDAP0-TzR$3DJ(ypu5o`k^dqxz@KSbroCxZE#})q2M=OlUkF?jT|?# zO)*Q+au~lj(I)n_DB;1$>^{TfDSAfmv`0eS>Cy^pkrxGEGs(W587|83FTRf51*r17 z&pNDaxWC;pp4@n5Am}i8hiUX&v-@(3G)@Y;#P9W+!5>KLwhXs$STvTz>_wmtPg?$F zn07^x-2F3G>90pn`x8*ArL&RN^_Lk!KqAQ2E)6@AiaOskW^oTolISecy#1RYEGHxD z!lCI0R6|{9S4K%l7%-`25d<`@A%Fg40CI8PW*45qCQ&oR0w;#)fBhEK`b!S={C&In zs3&#wUli5gRL84BT@(*-Q+VtriP6V)H~5Z=d_s4k#>Sgbm8NSMGpT46^05XidpWbf z-oY+6kdwkgD~2h-(Kp8S4IS2GOEj;us97b8fcaCN(+g6Y&WqmEio=QT+V66Od{m`> zBin|zi#~TWE|7pK@0HD)JX-cN4oG=I`$5qdp&bL#aGT$;NFD98U>sRpP4!T3`^9JjGc7f5;lN!v#-HBgJH$Vz2rqQ3^SV~Jxx zjo_y|s>mI+*lkEXj{1OVu3DJhk!wKBETguv_L$bWpgSxzzZvQYKz4fRkHt{^ftLmj z_?y?LUJ*hPo%aUn;6x1B8AKN4q8$ymhQgNtIqY{1f4u&6U^m^mu}k)EfcFAw5A#}U zTz{xa-`|(xL8bt24Ft`{j{;e7!xm|(;tQat!3-jff{72L4;lZO;M8Of_+2%+kw!vVe+6)rkU(r*Sa@YDLgYfsGI7ldw`{#SDUue-Bb978<-Qg^S= z+pOdym2rBow=|Vsn*J!D;qT`W^v7DDG1z}0?|;29tCpaH?T5fH0_XyWB;|vloh3ra z%24VT+M7R==l|*?fQPHW+Y5R0qu4I+|96LA!;madIDnyEKoD;DiH9c9uO@ps`~;EY z%XXflbOAX61o-iL*GWoAjw-YC3lMZNHv?!%kq_C$j0_~@5!%*kDC$(X!CDY74hv~K zM7>#X0ELwUNI*|X>ZaJEWHs-?p;nA-wxx^`4Tc-T?huPu6luSQ#ec`z1FED$4dp@hq)HAEFQ#XS%`Rl6!$ zjXgnB>E=0d?PHz_`>-gDwY=_)?~SUDEH}CQC1FnfsK1}I|8yNg?YmH7TOR<%@c&+^ zhg;a)PG0+exYYmo76047{UeKiWbv;YpMUh?AHDcL(F=|LaFc`Bjf}6OWofx!XTuOs z3E=;zLR)}NEIs(=C37~Rq=8e}RemovN{X$+%nt002I{;;sO(MjGq3T}V{#A6iTcG= zd1Ky*yKJkEQXVD$N`5}}Yv3Hgi($RzpR?sTIh9%mEQ4O=E$N?*R zaN})_c+Hr#{lqE6M-%VS*vnHnW8+t&XQM`KyNAM)uKnCTD;6J-&s(%>4$7Z85BPf9a*qnUDvS4vEjivaY{S!I;b)l>?H5)68@=?}vnnppS=Y zUn3C>FmEYqKgaoFBJprKr49cPvEZ=2{F}8ZHw;ITp)icttYV6)ztvtC|wzDz3la48wv|>rIg7(Z_1Z&yRq0YaSux!GyFDRUD)BhBjkH*ML0hx*322;q?OoCUqdf z6r~Sk&|hP)`-5QW%WUj$QTYgyM2HXfXsBh$Y7pZPimbavb3qX~p>*MlpZ79wKn|i; zai4w&c-+xOv;r{g7y`BV1x23M0=f$=Gm3iXM>_#f2jC+A?P;KFjq(5TNBitYPlGG$ z0go5RFzf;jI3GaBgE~9`-(ju;qKwY~O-=%cdet)k112*`1HB{wyUqW8(8zcy^moa`{3$gt@ZZD| z^S8f8sQu9SyHG%X$m$e$~F|Hrb80OY!<{i++_jh6xv19*7;{$#dy)bP*M{h<>;B=WYnXLu3t zv~7XN3<$FRc>HH$|2hc&Z0z3-`#&f4Kdz~NPVC?A<$tc?|7n5#xr+a>vH#WY`p3rp zhkyBx^Ynl0Q2)QPu?3twLzUU{&);nxyTyM-QT4?S9_S@*fwHg!5zP0BZI(gV<6>4R6`j955nuTpJ}i^I0Af~+y;O%$6d|pub>)q=)$mpcsHlw zC<#HK1RiHQA(faUXZXk83}@l5n&B#K>p=ROvA8clfUHMnlRgEE>G&~NJQuGX`egJ2 zcON5Ri4hXqnA@uPJSz#Tcv}Pwgg_t3CX4#OpKqwz<$fMp{aeEwj%R}1ue6?JsG9Nx zPnu8`Ro0p3upC$i6faVl{H)O1ux&&@e0ZnIHpt_rUB{}a1GlC1wyaAhekk;5hky$&nAuJww+UiuMK17Gc(X9!!>oZ_%qyhP=#CX3rw z2im%WC2mXCxad&wzTar2y+_%jPtiw!Xz=)cGY!>dl5y7klt*60Y1O<`%6hh#AcAqu z-Ga^2UhSjE+JOficsFKJafR(O0>9KPf0SnFYY$TvDW*2p#m{Dnt(`%#46}2Oa9yLF z{t!S!pJ+MMTf|QM@r@wAf+b~@l#DQ8*`lqV+dp`Y_Nf>hzdYW3O7WurYZZ@_l})yX zag$L&SZ;ylW}e)LUQtb@ul*W`a&$SP#D4wG3@D5T8d_^c2$l4>s1j68oQoZ=HBF4m z`?$IA?DF|8ud2JI^C$U6HdF)bkSa-ybYb#ACJdluyh_J@9le7eDy@89RM%A3`Z(NU zG6{F`jI2RlY|Mc2N=`dsvV0_V_g#a80wHr~7bq*|t3MbNN}OFw{6Nu^6MAb4AKX_f z^kZ!%nG`yY7?cE0DmlOARG4`A;=~F42Z@Tr-R81S()PEKMIOlZmaNQHL5;@0>=cR4 zv3;_=oDh8Hu%Q;bfm5xufbb<0lnjJ`ML~UxeC-;lYy`eHkcCpnI%52 z$HVQ4Is(qCClURkBr`J3@Dsz3uC93U+FkvcD^B8bF=HZxk%;(NyM$sg+GN+#1$@#6QcG<$p_l zZD8Ggf1{jF^5#}vPCwRfCFKAWyMLU6P%lLLT>H$6B=Ufm(KLN@IbA}Ht+XPeSt$h_ z3ek+_`feyI4!K=fM$266uv{y>C}<>fsdKxshlLiYqVpMol%*x1DpbU;j)dCwQq_HO zpzUAEr8C)$7F+u?&2L7AUAn7tS<%+*8mz*&x%}>=WCxK%mOd$hFP3h9uzCsmg_zhVc zuE`!QWBe)zvm4~((zPaEyqP!9GjKBoCFzOw1hpQiAm^VGHfnXm_Iw}mpVp6*w zKYhviE9C6yZn88*aru0}IQG1|7YW?5S|rj??G;iXDfVlX5EJI|G}s5Xnb!60- z^{wG3sSqTV-M>Hs=}%GgZfu>N&5LsHIk5`jkVFcnpN0$%)L)v0W#E)}UZvdGD>&s* zwznI6o1RRwP1<4Geh9Y7HXCe#jHP0-E}W& z%09(nW4gxE=NIhB!-a^rAb@VXdI+ArW`am3QDOry$8#(%X9zBheKZxgse_IE{-o3x3VH6*L8#rqV# z>hy%!e3g6qJg)EVUjgQzw@@_O?m*-2$6z7HGSLPx2^_(vPBuJj4N|~(Ws*e zPn|#BV9Ez+_qZt2aW?CGvchWr zIaL3@`g*LOFgn~HEfh_-#9PnZ7<+KRWTm)(o+*8J5D4_b=P+21q^S`pAv8ar2jEjm z-6N#lZ-y%iKpxeqAGIWme&j9>j3s(^oZaX)2&gj=A7jZv=>>o_4ND^Q1S`OK4f`u{ zE8?4Dp^2=F#ILtYTOaezIV2o0euS`yd#Ol9x6wo(M1w$*9^v>x@*V)JaKtRq&o5#s z%d0S?6G>u_2qc*yQfO(lWf4YYiBkm8#W(IUo$TSjkCn|!#ow7m72vL)AGB2;54zlf6;8h6Lcysg8`;LfnT3c`Z zxELn|c)@l2KCRMgAmF=s$a<7hWPnq6>T16S=)&p<_8h;>P?5r|FZ1Qk1x%0Jj)HP0 zA7btwo4!d=GD)g097C7p>9Lovr6{R^8Unw#(~-)q$EX|nHT0F(*U00?J{?Un4Q_h) znMK!8TD^e(!*kaJ)m*Xc+~JA-myQTn<<6Nb{A)~;xi{YtxWGv&oJ_swKYjU~BCpH9Sf{OP?u6d_U6-c`U9SX1-9_T}LmBNw(7uL$2dxzJrai1y zIo66L-p2;XRKEU-yhQ{zO$X6siS-!k!sTju82*;Fl;FAhMG7?sS46z?0=t6->t&=i zbi)?|#8C~Z)MvAXfxtYki%U?BqFOLy1R>U8mG;wb5~RoST6v^fEuk#| zN64?A;XkNA;f@G`KKL<_;62<*kPTNi&~&MPII-l{j*mQ`b>H-_Lv zLh8>w0dW}?fP$1Y^K*E^c8H~`AowGwLTLQ?(zSL5MFJ|gZuJjj(w}&%jt7yMGkYi^ zs{1#C4kMSifhu?gm9*>Wofm|)28guk8Ic@BL#j}^7xfxtU3PmNJ4QiO(A(fbyhyD4 z!7Xa{*aXEjl5e5jh`j2Wy8>oHY7mw1BWQt$pd$ouBAiWPf7J zEa>enT&n328H4XR_dnV@@2IA>ecyuxRD?*CYLp_qDMbN6#85;GMY@nJMVf$80|ufX zqCvWdf)qid6GR~N(2GcK5^6$|o}fU0B>OJUyKlUW_w4=d8Ry(F&K<))))>ji%vvim zbFTR-pYLzNq1WFqoQDgy5Tvh692Mu^?hM*85u(c%j{S0$RPEaQnJ38eFFG$F6T6vB zxiFd6vs;O`I=NCt;={|N+{dHC!5ltN7We@@hX(?xH;Krt_u2UNEIZpND4-~~t((~) zC*4)p^Wp|~2XBG?$G5cBDxFZ-VD?CM)-M?^W_~5sUQhfm6`?)9WE=#AmeLQ%a@H=J|!zvXz$n zdE9?}4{DH)aWY9&)%fF-+Yi1iO0%IBsYsiIxV|$NCIJ4Ps_to?@ATvrt?B-Fa964z zQG%TMz}*VS8&;)7_&`rskKRpd+Kp_@RC?=nPG_F=3?|Ohn2G*ezT{zZNmHP>VY5nj z^Ewm74pT)6E8xv;nP4*Le_s_1@f0#h>Sv71X61X{9@TB3GcRr^Ut72NU}_&Fw-5dE z@tFfsy$1j>#cZ`;);biY{{XXHjcuuxPM9e43pm*XRGh*zZ>Mps*0_@-Tk60h+Yj%Y zN32*9Jk!ZuHY}}^xHVnjN*80d&PtJl$kNlS5`uY{c6|^28!3AX@b^=AX>_A1`Wdh9 zLW87kJd{@p?il{`PJdtM+2pg?TOSW7eVDQd8d!US-JJF`+v3lElWR}mlV{PW49ZB9>BE^Jf7%9$+j z4=#7xa1Y47#uPr{0Z&Pe`mrtH!J9G2+YX=f?1p*|yVNFOtd;nxe)7k;x zZYV#+d=)%8hW+p{`^#v+14Q2fvMrS|r!i~~mVs9Od9PlHHz*sjo`Yk%#R1@=dZ-kW zLJLF#(onrqCZxnIt$vycLaSzQvrF4Mb19W!umE=kS4K z-;hGvfvC`WvkkHh$+QXOLs$<`AdbXLQo>c zNmG?eA-xKI{O17W3t_y6ZQA_YP6syax3aZr+6N=#j+F5Z%&UbH_80$vmXwhx?N6!F zbS4f{@$x(Sl)6qXALM$b{4#UhUJq@`)pAEWuAs*+(RjHA`Q}|MXP-Wa83rc zdFnv;Io2BhjnFO{-`UOcRJb^dAg2LO_u;bB!Moq?TStOCglXfaeHesV}T=$s|%c;+;M^`B{h4U5_}PG_J^!5{#W z3;jgRNoopX{NS2_osyox!# zLvgYVslvpbhnvaFUXr!S1n<^Vo>VcB+j%_FA~m;|D>b*^j$RJO7{>YK=}O;}Z%{lv z>$)dan%pUX>VdXa8-+u?&4b5H=?;~SiQ8jc$}CTbSuyb}JUb?&ix_1+c17+TL&A&m zw>70M%MiDpeg_I4e*z^QZ!=tRQTcA( z@AM8?MfUdk9#xo7e1FrK))!dJ=d8&Re(qX2!z@bQ+_A!^a*@OMV1wbsQ~6pnYkJD(&h5!UlsP+a#3eM3x+eb}K72a14}|B6@`B0np5%oa>m+_Og9 zB?7zGZ30D;nA|Su>#1BS;8n`Z({f>7R6?JIerytKtJ1zBq1$11zuWD>)^%#;Dxg2` z#AVJLPg43=;Hu8mU)lqbNppYTP=^fHFXWO%N{XShcNQrw_HX4*J)g-#gm)jM2 z$Hu+Y>-M%%ao2ejrZ5qm?VN%7T%1vZ+*+#}C#iUnZc%ZE8hmaA4wyFo$_PV-yCg*D0l)62vHI99dpW)_{mN%_!l#8g(-?*5 zyY&PsZC0SlCQ~^XsJM_=2NvB!Y}v=@zXG`qBbW+p5Lte-U#6_*5L`%~B>EJgV zT4O`^wuMcGH_yd zCD+DQ|D5Z&E)U+};jh(l$wrnvNptt?4mW{covzbyD+ws;-BUt|<%s?5Ifj0L@Fy|i zUncHpkXh!}w@~CTyv?ySAP&1S;a(;-GpKgi%ua;8tShtni1q9(!P~ms>o59)JEvG_ zJmko#(xfiK{#K} z=*}iL;7TAY+1`?t*VzPA9G+~LeYscMzVb9K74>=PZLvOmm!@_K=SE^=jgixI^k_8x z5~dX#aY~siO-K$B0XCY6v}>POR*uo)FzJw*wCVrEB>SqMh((mI-oDIwPZps=b|Qcx zt!&WY8ZMsvl&eFtdXyAK;~{BLOzi)JiTM%7!o;P~*{vSXVoTfEG?HjWBO@K0V&UXLCWivf)1Fq267(a}XCG zXeAm-(E!4Wj3m#HI&NSsEi5Aimlfe4d>5??-SiCv2^ONMvO5j}gDS0Fmv7$Pkk1x8 zzo1V1QRVP*2CAN%KT}c1MUf?mKFfZ#5Z+W}Gn^}|d(?&NNRn|ni`SJI6rEGEM#LmL z8Dh^o5}^jguOGL*rQZI2s7&l`oY{A?*ca?8lF%kwi2*g2Oi0ex-N+|}**$3zOWkX&QyXRQ7 zg&jS+BOSGhY7zBCycqYLz3L72?1ON|-u{tk;|cEeqV-OFgoRK7fHLZ7JX1C#kynGV zW&^F;!{zU_V@udL?mc}IG(<<=55UN*!Jo~i%EMQ+rq?6t#PvPH*6|a5owO4ZCk;z2 ze9^28jy^K)<46|IIFrP(Xf0X{b6m zPv%MBi9|a>k}q@ns(@x&>~y)bT6HeJlc{wBa@zP4w^Uf-y>_1bd(H{MJ%$-I*sTa^ z35}oDkv7^!V5s&@hva*3#UmYTC$z+E^XE00(mnR{n4|8ameg4gj>PS@DWGpN8!`Uo zyIgN8a1+qm_Z_z$vM5X3csduv&7A!~QOU1j4Q=n%jNOoN1#hm3(n4G}jrM0ubTom7 zsO|w^XWD(oep3;!IC+0qoKV2x1X%0utd|*q6?q1*VVCETRQ^rCvP9Cv-(2>tyZEJY0T!grx#rbun}CtqThqCTdX=??volm4Mn=9I zTFurN%nSa%$|1fjR$6&k@!Q>L4^>l2%mA; zejq=5U=&MS?kry}5g1WPscHczc2!E2BT_Lq8+d)FG(`tWHrbPWMuCwI-mD-eMcgO2 z<*#$PvO{xgQn{*QizofpZmI}By3P7X@F?9k^+1vhdy5~SYQ;Keg!9UVBVdQIPlQP7 zx!DxWL|bxYfivq@3`yzeueck|lF)YZBAm!mq_(E=Ns$2s=+R|!E8nOxy1vPvYx5@u zPO}x(_TacKC~IGHOi$zy_G=q>VQi%eRQqB`wg!vBi)LC>kYRuYqQT+JJMwG|p@lDW z`QF7lzJ!4~WmyGSi&MljXBFi0G8-o2a+2b67(05ctU{KTi+%tQuqzBW zVycg5c$u0ii+?-ETep~zFr4dGvR3Mb?5WlZn;3X7Nwc2vn5Y&aXpyE`X&NC-&4x?1 zX9j>QRfJzL`Q(k_C^M~$C1>|x!rJKyaf$OwWAC^LtwO1<_Uw*8YL0SCT@f?1jF4~3 zRf}J9`EGj6-wXp-fFS>`E2WyA%S1|?t-JCdu#WC`+4#_+NYDO&Yl0d-0E z`=$AAYmHN`D!vmhjJVF#zufiVDiUs|VXW#ga8@2yRx=f2oW8+PEYIDN_iP(ZeQ}rNT2y@rttBRep~*a zD^QSy5?bJmRW9cFWY(KVkt%3uK!}o~nFDi5)(bZI7!^~TIL7z3h&xcm;cqn_4lcj| zQ9e_h9IXddf^70+gu|fZ0A!J~)dOocQR^X(=@2DGvD0#zXAo=dE#)%@c{IU!oTeTH6TVf3jjY|w?~Ss zxhH3hU?hJeNLx4Vmg4*$t6hIGzt9*$cXw4$aJp>bqX+d<)f3POn}TLJNsK!fguTP$ z38MIt7@Lu-t^@FoEmol&?(Yol)1ko3i|;5eU-qs2R-m)n0e4}!!NCT~1!`HK+QkL* z-_j)r|0cJjp<*R|ocs|VzA`}K>clHX*RT5H+a9A4$}DJ+t=btIvn9zr&l8O!(ic;t zm8t2lYscOO9AQncE6{F$SyIjco09c}o?k#ZOV;4PlO(Eq*=u;nc=l>&eUR}(s1$8^<_r|G`ob< z9Q}P(yMvsE%j2Wmyii(djQI5?SOkn7D4&OAB-=MsL7Obg^bf*urGf7;e&uHK`r)s+ zdYc@u)zlfnd44<2o00yHs;WH0aM5kz6gSs8g?@DoE3!{M^}P+d#h_@dN%6{;xG_Oi ztnC93<~c)9V!1p3ONV__Ckc3a4ao3QAX3{(gKTseD6GZ>mj_SNvk;E8 zjDCgMJ~DrH2bw4`onYLNz`bda0bm_7TghbeBDb_-n_zn9)C1Ln=%S+avQ?GsRj~8G ze3@>abe8`_m7$lm97yqdEvJY7SDn*F5YEG4MkM8MDavhpt(NZKnUh?+S*0)iABPNe6`^G>L7tcJKqxMlPX(eX`^>=Oi%*dA1}wWr7OUiH$IQKL~C zQ$a=_V{J<&NpaCj{wtV0Zn#Oa)w^J+Aif#U6REqKUpFg!WVx1)Efy}_7qqvmz#QKw zY(NmZ(_fg$KPm+kiWOeU{J{SdcxHV5NWe0YAIxA@o}pc)7$_ju)CI|O*{(9tT`g;YSBDndMHEHWD3Ee=GA+0x4Ra-v51@)^V zRa)B`Bi_xsMYu@6PSy05nPY9AlIiQdh=ykrcEz^?{huR7Q1l$#Yf8#)6A&dxXnETc zQe^sV)b%6uYO)4bQ*=*Eh!GsLo8AYQ8EUq1CX-;(-EU{GQNPn2t1)--b~=oH7R(12sD#lbs`Gnf_bG!q?qhqxW#W6g}zuJB1% zm6;h2>%&O0Ooyn1E~&6v4=c$nzBC-O*5a(Kt&%c=upQEk1$Oe}r=z2zH}2DQ+#eho z(%EOHsXzR?F}+seR<=UmVN|3#sUGv3!7PG#BTD-g@957K+I2?fdmV=#eY2NW?UG97 z4!NoDyy=3lk5KKcJk0J;c@o|+W?e{?m8twk&<_Be|0tEp;k{|*`A6a5eih;?n}7Cm zCRM0Yp@9SrdY`{o`(bOloasAJ)mKP3P&s3tsPeDWN`YHkkAJB*e~J9|joe?dTp%vY z|5wxImn`>}-ujo``j?RYKZ`2>$-RBb`JdkY64C>4u3u~HuQe7Z>G3~S`a;pJ$*O$t zO@Xn%w3Gc??Y1KBgZi_FK_`~H_0nPD1M4UF0_g8J7h}a|@g0RpnFQF*Nk!1^Ry+VJ zD+We|{$Id-U%uRkI0A6-Na_O}fQv@~T)g5BE<*C5h9kmXT=De=) zFh5i9!vlpwHj>n<*v)Smw8+5Dfx0uJu1GdT7}Gm*EyKPQX5Q^Nk zcj<(juD{3^a8O9)1*7%8`~P>(|KA+!6&kyKAx`yaf_265r2>r;2G)61=-sE-<#`a5 z_XWN8K4>stPW|cb%Oa1_U9KZ}YT-W1+zgSGJ0QZBX@jnpn5P0@o5~ z8L-_QU<_#2S{0hjds}VK4WR|falAh8}ar)(8Z7#_J%z@Mq!b8JaS%l$;c+NzFB@DwQd2T;k=0j0fY$-W!07n z3_O`(!n8cZJA@mZA3TsG9GLx#A|Qi(>v~F*$Xt^M8&mNudVMyh@Lpf`sAE#UqJOH0 zpi!wd-e$&&p{sNG`^{`;Z2@eDZ2$7dKp*k^uFfh9z;$*{y0{JQJZM&DAli{TyGa^N zHvX1G1seYo(9y+Zynf*o=`)W%^1Z5SkFBOkG*u?|LG)>}x*n zsQWErvZL%xCh#ON88w0VMdiA~47i`D#}&Q#cwKW3>o%)0SaOHiAC1+Mc? zp2O4^w#kYd`3&Awlo&D{LJmTJA1#OcI+)IsDzYEhi++Zjy)~$@jDu1S4J}1Ic?97w z{x4;we-7%I=j|iK3=d!We=ByGsm~u&OG`t}cmAD+;6HM2zlQ5SIV}Hddi@%%|Hv@> O@3#G?hpWc#qyGWH=e)T9 literal 0 HcmV?d00001 diff --git a/lib/ICM-20948/keywords.txt b/lib/ICM-20948/keywords.txt new file mode 100644 index 0000000..7877145 --- /dev/null +++ b/lib/ICM-20948/keywords.txt @@ -0,0 +1,193 @@ +####################################### +# Syntax Coloring Map +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +ICM_20948_I2C KEYWORD1 +ICM_20948_SPI KEYWORD1 +ICM_20948_Status_e KEYWORD1 +ICM_20948_InternalSensorID_bm KEYWORD1 +icm_20948_DMP_data_t KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +ICM_20948 KEYWORD2 +enableDebugging KEYWORD2 +disableDebugging KEYWORD2 +debugPrintStatus KEYWORD2 +debugPrint KEYWORD2 +debugPrintln KEYWORD2 +doDebugPrint KEYWORD2 +debugPrintf KEYWORD2 +getAGMT KEYWORD2 +magX KEYWORD2 +magY KEYWORD2 +magZ KEYWORD2 +accX KEYWORD2 +accY KEYWORD2 +accZ KEYWORD2 +gyrX KEYWORD2 +gyrY KEYWORD2 +gyrZ KEYWORD2 +temp KEYWORD2 +statusString KEYWORD2 +setBank KEYWORD2 +swReset KEYWORD2 +sleep KEYWORD2 +lowPower KEYWORD2 +setClockSource KEYWORD2 +checkID KEYWORD2 +dataReady KEYWORD2 +getWhoAmI KEYWORD2 +isConnected KEYWORD2 +setSampleMode KEYWORD2 +setFullScale KEYWORD2 +setDLPFcfg KEYWORD2 +enableDLPF KEYWORD2 +setSampleRate KEYWORD2 +clearInterrupts +cfgIntActiveLow KEYWORD2 +cfgIntOpenDrain KEYWORD2 +cfgIntLatch KEYWORD2 +cfgIntAnyReadToClear KEYWORD2 +cfgFsyncActiveLow KEYWORD2 +cfgFsyncIntMode KEYWORD2 +intEnableI2C KEYWORD2 +intEnableDMP KEYWORD2 +intEnablePLL KEYWORD2 +intEnableWOM KEYWORD2 +intEnableWOF KEYWORD2 +intEnableRawDataReady KEYWORD2 +intEnableOverflowFIFO KEYWORD2 +intEnableWatermarkFIFO KEYWORD2 +WOMThreshold KEYWORD2 +i2cMasterPassthrough KEYWORD2 +i2cMasterEnable KEYWORD2 +i2cControllerConfigurePeripheral KEYWORD2 +i2cControllerPeriph4Transaction KEYWORD2 +i2cMasterSingleW KEYWORD2 +i2cMasterSingleR KEYWORD2 +startupDefault KEYWORD2 +read KEYWORD2 +write KEYWORD2 +startupMagnetometer KEYWORD2 +magWhoIAm KEYWORD2 +readMag KEYWORD2 +writeMag KEYWORD2 +resetMag KEYWORD2 +enableFIFO KEYWORD2 +resetFIFO KEYWORD2 +setFIFOmode KEYWORD2 +getFIFOcount KEYWORD2 +readFIFO KEYWORD2 +enableDMP KEYWORD2 +resetDMP KEYWORD2 +loadDMPFirmware KEYWORD2 +setDMPstartAddress KEYWORD2 +enableDMPSensor KEYWORD2 +enableDMPSensorInt KEYWORD2 +writeDMPmems KEYWORD2 +readDMPmems KEYWORD2 +setDMPODRrate KEYWORD2 +readDMPdataFromFIFO KEYWORD2 +setGyroSF KEYWORD2 +initializeDMP KEYWORD2 +begin KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### + +_ICM_20948_H_ LITERAL1 +ICM_20948_ARD_UNUSED_PIN LITERAL1 +ICM_20948_SPI_DEFAULT_FREQ LITERAL1 +ICM_20948_SPI_DEFAULT_ORDER LITERAL1 +ICM_20948_SPI_DEFAULT_MODE LITERAL1 +ICM_20948_I2C_ADDR_AD0 LITERAL1 +ICM_20948_I2C_ADDR_AD1 LITERAL1 +ICM_20948_WHOAMI LITERAL1 +MAG_AK09916_I2C_ADDR LITERAL1 +MAG_AK09916_WHO_AM_I LITERAL1 +MAG_REG_WHO_AM_I LITERAL1 +ICM_20948_Stat_Ok LITERAL1 +ICM_20948_Stat_Err LITERAL1 +ICM_20948_Stat_NotImpl LITERAL1 +ICM_20948_Stat_ParamErr LITERAL1 +ICM_20948_Stat_WrongID LITERAL1 +ICM_20948_Stat_InvalSensor LITERAL1 +ICM_20948_Stat_NoData LITERAL1 +ICM_20948_Stat_SensorNotSupported LITERAL1 +ICM_20948_Stat_DMPNotSupported LITERAL1 +ICM_20948_Stat_DMPVerifyFail LITERAL1 +ICM_20948_Stat_FIFONoDataAvail LITERAL1 +ICM_20948_Stat_FIFOIncompleteData LITERAL1 +ICM_20948_Stat_FIFOMoreDataAvail LITERAL1 +ICM_20948_Stat_UnrecognisedDMPHeader LITERAL1 +ICM_20948_Stat_UnrecognisedDMPHeader2 LITERAL1 +ICM_20948_Stat_InvalDMPRegister LITERAL1 +ICM_20948_Stat_NUM LITERAL1 +ICM_20948_Stat_Unknown LITERAL1 +ICM_20948_Internal_Acc LITERAL1 +ICM_20948_Internal_Gyr LITERAL1 +ICM_20948_Internal_Mag LITERAL1 +ICM_20948_Internal_Tmp LITERAL1 +ICM_20948_Internal_Mst LITERAL1 +DMP_ODR_Reg_Accel LITERAL1 +DMP_ODR_Reg_Gyro LITERAL1 +DMP_ODR_Reg_Cpass LITERAL1 +DMP_ODR_Reg_ALS LITERAL1 +DMP_ODR_Reg_Quat6 LITERAL1 +DMP_ODR_Reg_Quat9 LITERAL1 +DMP_ODR_Reg_PQuat6 LITERAL1 +DMP_ODR_Reg_Geomag LITERAL1 +DMP_ODR_Reg_Pressure LITERAL1 +DMP_ODR_Reg_Gyro_Calibr LITERAL1 +DMP_ODR_Reg_Cpass_Calibr LITERAL1 +INV_ICM20948_SENSOR_ACCELEROMETER LITERAL1 +INV_ICM20948_SENSOR_GYROSCOPE LITERAL1 +INV_ICM20948_SENSOR_RAW_ACCELEROMETER LITERAL1 +INV_ICM20948_SENSOR_RAW_GYROSCOPE LITERAL1 +INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED LITERAL1 +INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED LITERAL1 +INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON LITERAL1 +INV_ICM20948_SENSOR_STEP_DETECTOR LITERAL1 +INV_ICM20948_SENSOR_STEP_COUNTER LITERAL1 +INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR LITERAL1 +INV_ICM20948_SENSOR_ROTATION_VECTOR LITERAL1 +INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR LITERAL1 +INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD LITERAL1 +INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION LITERAL1 +INV_ICM20948_SENSOR_FLIP_PICKUP LITERAL1 +INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR LITERAL1 +INV_ICM20948_SENSOR_GRAVITY LITERAL1 +INV_ICM20948_SENSOR_LINEAR_ACCELERATION LITERAL1 +INV_ICM20948_SENSOR_ORIENTATION LITERAL1 +INV_ICM20948_SENSOR_B2S LITERAL1 +DMP_header_bitmap_Header2 LITERAL1 +DMP_header_bitmap_Step_Detector LITERAL1 +DMP_header_bitmap_Compass_Calibr LITERAL1 +DMP_header_bitmap_Gyro_Calibr LITERAL1 +DMP_header_bitmap_Pressure LITERAL1 +DMP_header_bitmap_Geomag LITERAL1 +DMP_header_bitmap_PQuat6 LITERAL1 +DMP_header_bitmap_Quat9 LITERAL1 +DMP_header_bitmap_Quat6 LITERAL1 +DMP_header_bitmap_ALS LITERAL1 +DMP_header_bitmap_Compass LITERAL1 +DMP_header_bitmap_Gyro LITERAL1 +DMP_header_bitmap_Accel LITERAL1 +DMP_header2_bitmap_Secondary_On_Off LITERAL1 +DMP_header2_bitmap_Activity_Recog LITERAL1 +DMP_header2_bitmap_Pickup LITERAL1 +DMP_header2_bitmap_Fsync LITERAL1 +DMP_header2_bitmap_Compass_Accuracy LITERAL1 +DMP_header2_bitmap_Gyro_Accuracy LITERAL1 +DMP_header2_bitmap_Accel_Accuracy LITERAL1 +DMP_Data_ready_Gyro LITERAL1 +DMP_Data_ready_Accel LITERAL1 +DMP_Data_ready_Secondary_Compass LITERAL1 diff --git a/lib/ICM-20948/library.properties b/lib/ICM-20948/library.properties new file mode 100644 index 0000000..b0dab8f --- /dev/null +++ b/lib/ICM-20948/library.properties @@ -0,0 +1,9 @@ +name=SparkFun 9DoF IMU Breakout - ICM 20948 - Arduino Library +version=1.2.8 +author=SparkFun Electronics +maintainer=SparkFun Electronics +sentence=Use the low-power high-resolution ICM 20948 9 DoF IMU from Invensense with I2C or SPI. Version 1.2 of the library includes support for the InvenSense Digital Motion Processor (DMP™). +paragraph=The SparkFun 9DoF IMU Breakout uses the Invensense ICM-20948 -- a system-in-package featuring acceleration full-scales of ±2 / ±4 / ±8 / ±16 (g), rotational full-scales of ±250 / ±500 / ±1000 / ±2000 (°/sec) and a magnetic field full scale of ±4800 µT. The ICM-20948 can be accessed via either I2C (400 kHz) or SPI (7 MHz) +category=Sensors +url=https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary +architectures=* diff --git a/lib/ICM-20948/src/ICM_20948.cpp b/lib/ICM-20948/src/ICM_20948.cpp new file mode 100644 index 0000000..ae86600 --- /dev/null +++ b/lib/ICM-20948/src/ICM_20948.cpp @@ -0,0 +1,1806 @@ +#include "ICM_20948.h" + +#include "util/ICM_20948_REGISTERS.h" +#include "util/AK09916_REGISTERS.h" + +// Forward Declarations +ICM_20948_Status_e ICM_20948_write_I2C(uint8_t reg, uint8_t *data, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_read_I2C(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_write_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user); +ICM_20948_Status_e ICM_20948_read_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user); + +// Base +ICM_20948::ICM_20948() +{ + status = ICM_20948_init_struct(&_device); +} + +void ICM_20948::enableDebugging(Stream &debugPort) +{ + _debugSerial = &debugPort; //Grab which port the user wants us to use for debugging + _printDebug = true; //Should we print the commands we send? Good for debugging +} +void ICM_20948::disableDebugging(void) +{ + _printDebug = false; //Turn off extra print statements +} + +// Debug Printing: based on gfvalvo's flash string helper code: +// https://forum.arduino.cc/index.php?topic=533118.msg3634809#msg3634809 + +void ICM_20948::debugPrint(const char *line) +{ + doDebugPrint([](const char *ptr) { return *ptr; }, line); +} + +void ICM_20948::debugPrint(const __FlashStringHelper *line) +{ + doDebugPrint([](const char *ptr) { return (char)pgm_read_byte_near(ptr); }, + (const char *)line); +} + +void ICM_20948::debugPrintln(const char *line) +{ + doDebugPrint([](const char *ptr) { return *ptr; }, line, true); +} + +void ICM_20948::debugPrintln(const __FlashStringHelper *line) +{ + doDebugPrint([](const char *ptr) { return (char)pgm_read_byte_near(ptr); }, + (const char *)line, true); +} + +void ICM_20948::doDebugPrint(char (*funct)(const char *), const char *string, bool newLine) +{ + if (_printDebug == false) + return; // Bail if debugging is not enabled + + char ch; + + while ((ch = funct(string++))) + { + _debugSerial->print(ch); + } + + if (newLine) + { + _debugSerial->println(); + } +} + +void ICM_20948::debugPrintf(int i) +{ + if (_printDebug == true) + _debugSerial->print(i); +} + +void ICM_20948::debugPrintf(float f) +{ + if (_printDebug == true) + _debugSerial->print(f); +} + +void ICM_20948::debugPrintStatus(ICM_20948_Status_e stat) +{ + switch (stat) + { + case ICM_20948_Stat_Ok: + debugPrint(F("All is well.")); + break; + case ICM_20948_Stat_Err: + debugPrint(F("General Error")); + break; + case ICM_20948_Stat_NotImpl: + debugPrint(F("Not Implemented")); + break; + case ICM_20948_Stat_ParamErr: + debugPrint(F("Parameter Error")); + break; + case ICM_20948_Stat_WrongID: + debugPrint(F("Wrong ID")); + break; + case ICM_20948_Stat_InvalSensor: + debugPrint(F("Invalid Sensor")); + break; + case ICM_20948_Stat_NoData: + debugPrint(F("Data Underflow")); + break; + case ICM_20948_Stat_SensorNotSupported: + debugPrint(F("Sensor Not Supported")); + break; + case ICM_20948_Stat_DMPNotSupported: + debugPrint(F("DMP Firmware Not Supported. Is #define ICM_20948_USE_DMP commented in util/ICM_20948_C.h?")); + break; + case ICM_20948_Stat_DMPVerifyFail: + debugPrint(F("DMP Firmware Verification Failed")); + break; + case ICM_20948_Stat_FIFONoDataAvail: + debugPrint(F("No FIFO Data Available")); + break; + case ICM_20948_Stat_FIFOIncompleteData: + debugPrint(F("DMP data in FIFO was incomplete")); + break; + case ICM_20948_Stat_FIFOMoreDataAvail: + debugPrint(F("More FIFO Data Available")); + break; + case ICM_20948_Stat_UnrecognisedDMPHeader: + debugPrint(F("Unrecognised DMP Header")); + break; + case ICM_20948_Stat_UnrecognisedDMPHeader2: + debugPrint(F("Unrecognised DMP Header2")); + break; + case ICM_20948_Stat_InvalDMPRegister: + debugPrint(F("Invalid DMP Register")); + break; + default: + debugPrint(F("Unknown Status")); + break; + } +} + +ICM_20948_AGMT_t ICM_20948::getAGMT(void) +{ + status = ICM_20948_get_agmt(&_device, &agmt); + + return agmt; +} + +float ICM_20948::magX(void) +{ + return getMagUT(agmt.mag.axes.x); +} + +float ICM_20948::magY(void) +{ + return getMagUT(agmt.mag.axes.y); +} + +float ICM_20948::magZ(void) +{ + return getMagUT(agmt.mag.axes.z); +} + +float ICM_20948::getMagUT(int16_t axis_val) +{ + return (((float)axis_val) * 0.15); +} + +float ICM_20948::accX(void) +{ + return getAccMG(agmt.acc.axes.x); +} + +float ICM_20948::accY(void) +{ + return getAccMG(agmt.acc.axes.y); +} + +float ICM_20948::accZ(void) +{ + return getAccMG(agmt.acc.axes.z); +} + +float ICM_20948::getAccMG(int16_t axis_val) +{ + switch (agmt.fss.a) + { + case 0: + return (((float)axis_val) / 16.384); + break; + case 1: + return (((float)axis_val) / 8.192); + break; + case 2: + return (((float)axis_val) / 4.096); + break; + case 3: + return (((float)axis_val) / 2.048); + break; + default: + return 0; + break; + } +} + +float ICM_20948::gyrX(void) +{ + return getGyrDPS(agmt.gyr.axes.x); +} + +float ICM_20948::gyrY(void) +{ + return getGyrDPS(agmt.gyr.axes.y); +} + +float ICM_20948::gyrZ(void) +{ + return getGyrDPS(agmt.gyr.axes.z); +} + +float ICM_20948::getGyrDPS(int16_t axis_val) +{ + switch (agmt.fss.g) + { + case 0: + return (((float)axis_val) / 131); + break; + case 1: + return (((float)axis_val) / 65.5); + break; + case 2: + return (((float)axis_val) / 32.8); + break; + case 3: + return (((float)axis_val) / 16.4); + break; + default: + return 0; + break; + } +} + +float ICM_20948::temp(void) +{ + return getTempC(agmt.tmp.val); +} + +float ICM_20948::getTempC(int16_t val) +{ + return (((float)val - 21) / 333.87) + 21; +} + +const char *ICM_20948::statusString(ICM_20948_Status_e stat) +{ + ICM_20948_Status_e val; + if (stat == ICM_20948_Stat_NUM) + { + val = status; + } + else + { + val = stat; + } + + switch (val) + { + case ICM_20948_Stat_Ok: + return "All is well."; + break; + case ICM_20948_Stat_Err: + return "General Error"; + break; + case ICM_20948_Stat_NotImpl: + return "Not Implemented"; + break; + case ICM_20948_Stat_ParamErr: + return "Parameter Error"; + break; + case ICM_20948_Stat_WrongID: + return "Wrong ID"; + break; + case ICM_20948_Stat_InvalSensor: + return "Invalid Sensor"; + break; + case ICM_20948_Stat_NoData: + return "Data Underflow"; + break; + case ICM_20948_Stat_SensorNotSupported: + return "Sensor Not Supported"; + break; + case ICM_20948_Stat_DMPNotSupported: + return "DMP Firmware Not Supported. Is #define ICM_20948_USE_DMP commented in util/ICM_20948_C.h?"; + break; + case ICM_20948_Stat_DMPVerifyFail: + return "DMP Firmware Verification Failed"; + break; + case ICM_20948_Stat_FIFONoDataAvail: + return "No FIFO Data Available"; + break; + case ICM_20948_Stat_FIFOIncompleteData: + return "DMP data in FIFO was incomplete"; + break; + case ICM_20948_Stat_FIFOMoreDataAvail: + return "More FIFO Data Available"; + break; + case ICM_20948_Stat_UnrecognisedDMPHeader: + return "Unrecognised DMP Header"; + break; + case ICM_20948_Stat_UnrecognisedDMPHeader2: + return "Unrecognised DMP Header2"; + break; + case ICM_20948_Stat_InvalDMPRegister: + return "Invalid DMP Register"; + break; + default: + return "Unknown Status"; + break; + } + return "None"; +} + +// Device Level +ICM_20948_Status_e ICM_20948::setBank(uint8_t bank) +{ + status = ICM_20948_set_bank(&_device, bank); + return status; +} + +ICM_20948_Status_e ICM_20948::swReset(void) +{ + status = ICM_20948_sw_reset(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::sleep(bool on) +{ + status = ICM_20948_sleep(&_device, on); + return status; +} + +ICM_20948_Status_e ICM_20948::lowPower(bool on) +{ + status = ICM_20948_low_power(&_device, on); + return status; +} + +ICM_20948_Status_e ICM_20948::setClockSource(ICM_20948_PWR_MGMT_1_CLKSEL_e source) +{ + status = ICM_20948_set_clock_source(&_device, source); + return status; +} + +ICM_20948_Status_e ICM_20948::checkID(void) +{ + status = ICM_20948_check_id(&_device); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::checkID: ICM_20948_check_id returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return status; +} + +bool ICM_20948::dataReady(void) +{ + status = ICM_20948_data_ready(&_device); + if (status == ICM_20948_Stat_Ok) + { + return true; + } + return false; +} + +uint8_t ICM_20948::getWhoAmI(void) +{ + uint8_t retval = 0x00; + status = ICM_20948_get_who_am_i(&_device, &retval); + return retval; +} + +bool ICM_20948::isConnected(void) +{ + status = checkID(); + if (status == ICM_20948_Stat_Ok) + { + return true; + } + debugPrint(F("ICM_20948::isConnected: checkID returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return false; +} + +// Internal Sensor Options +ICM_20948_Status_e ICM_20948::setSampleMode(uint8_t sensor_id_bm, uint8_t lp_config_cycle_mode) +{ + status = ICM_20948_set_sample_mode(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, (ICM_20948_LP_CONFIG_CYCLE_e)lp_config_cycle_mode); + return status; +} + +ICM_20948_Status_e ICM_20948::setFullScale(uint8_t sensor_id_bm, ICM_20948_fss_t fss) +{ + status = ICM_20948_set_full_scale(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, fss); + return status; +} + +ICM_20948_Status_e ICM_20948::setDLPFcfg(uint8_t sensor_id_bm, ICM_20948_dlpcfg_t cfg) +{ + status = ICM_20948_set_dlpf_cfg(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, cfg); + return status; +} + +ICM_20948_Status_e ICM_20948::enableDLPF(uint8_t sensor_id_bm, bool enable) +{ + status = ICM_20948_enable_dlpf(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::setSampleRate(uint8_t sensor_id_bm, ICM_20948_smplrt_t smplrt) +{ + status = ICM_20948_set_sample_rate(&_device, (ICM_20948_InternalSensorID_bm)sensor_id_bm, smplrt); + return status; +} + +// Interrupts on INT Pin +ICM_20948_Status_e ICM_20948::clearInterrupts(void) +{ + ICM_20948_INT_STATUS_t int_stat; + ICM_20948_INT_STATUS_1_t int_stat_1; + + // read to clear interrupts + status = ICM_20948_set_bank(&_device, 0); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + status = ICM_20948_execute_r(&_device, AGB0_REG_INT_STATUS, (uint8_t *)&int_stat, sizeof(ICM_20948_INT_STATUS_t)); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + status = ICM_20948_execute_r(&_device, AGB0_REG_INT_STATUS_1, (uint8_t *)&int_stat_1, sizeof(ICM_20948_INT_STATUS_1_t)); + if (status != ICM_20948_Stat_Ok) + { + return status; + } + + // todo: there may be additional interrupts that need to be cleared, like FIFO overflow/watermark + + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntActiveLow(bool active_low) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_ACTL = active_low; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntOpenDrain(bool open_drain) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_OPEN = open_drain; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntLatch(bool latching) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT1_LATCH_EN = latching; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgIntAnyReadToClear(bool enabled) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.INT_ANYRD_2CLEAR = enabled; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgFsyncActiveLow(bool active_low) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.ACTL_FSYNC = active_low; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::cfgFsyncIntMode(bool interrupt_mode) +{ + ICM_20948_INT_PIN_CFG_t reg; + status = ICM_20948_int_pin_cfg(&_device, NULL, ®); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + reg.FSYNC_INT_MODE_EN = interrupt_mode; // set the setting + status = ICM_20948_int_pin_cfg(&_device, ®, NULL); // write phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +// All these individual functions will use a read->set->write method to leave other settings untouched +ICM_20948_Status_e ICM_20948::intEnableI2C(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.I2C_MST_INT_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.I2C_MST_INT_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableDMP(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.DMP_INT1_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.DMP_INT1_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnablePLL(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.PLL_RDY_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.PLL_RDY_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWOM(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.WOM_INT_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.WOM_INT_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWOF(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.REG_WOF_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.REG_WOF_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableRawDataReady(bool enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.RAW_DATA_0_RDY_EN = enable; // change the setting + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (en.RAW_DATA_0_RDY_EN != enable) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableOverflowFIFO(uint8_t bm_enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.FIFO_OVERFLOW_EN_0 = ((bm_enable >> 0) & 0x01); // change the settings + en.FIFO_OVERFLOW_EN_1 = ((bm_enable >> 1) & 0x01); + en.FIFO_OVERFLOW_EN_2 = ((bm_enable >> 2) & 0x01); + en.FIFO_OVERFLOW_EN_3 = ((bm_enable >> 3) & 0x01); + en.FIFO_OVERFLOW_EN_4 = ((bm_enable >> 4) & 0x01); + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::intEnableWatermarkFIFO(uint8_t bm_enable) +{ + ICM_20948_INT_enable_t en; // storage + status = ICM_20948_int_enable(&_device, NULL, &en); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + en.FIFO_WM_EN_0 = ((bm_enable >> 0) & 0x01); // change the settings + en.FIFO_WM_EN_1 = ((bm_enable >> 1) & 0x01); + en.FIFO_WM_EN_2 = ((bm_enable >> 2) & 0x01); + en.FIFO_WM_EN_3 = ((bm_enable >> 3) & 0x01); + en.FIFO_WM_EN_4 = ((bm_enable >> 4) & 0x01); + status = ICM_20948_int_enable(&_device, &en, &en); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + return status; +} + +ICM_20948_Status_e ICM_20948::WOMThreshold(uint8_t threshold) +{ + ICM_20948_ACCEL_WOM_THR_t thr; // storage + status = ICM_20948_wom_threshold(&_device, NULL, &thr); // read phase + if (status != ICM_20948_Stat_Ok) + { + return status; + } + thr.WOM_THRESHOLD = threshold; // change the setting + status = ICM_20948_wom_threshold(&_device, &thr, &thr); // write phase w/ readback + if (status != ICM_20948_Stat_Ok) + { + return status; + } + if (thr.WOM_THRESHOLD != threshold) + { + status = ICM_20948_Stat_Err; + return status; + } + return status; +} + +// Interface Options +ICM_20948_Status_e ICM_20948::i2cMasterPassthrough(bool passthrough) +{ + status = ICM_20948_i2c_master_passthrough(&_device, passthrough); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cMasterEnable(bool enable) +{ + status = ICM_20948_i2c_master_enable(&_device, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cMasterReset() +{ + status = ICM_20948_i2c_master_reset(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::i2cControllerConfigurePeripheral(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut) +{ + status = ICM_20948_i2c_controller_configure_peripheral(&_device, peripheral, addr, reg, len, Rw, enable, data_only, grp, swap, dataOut); + return status; +} + +//Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. +//https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ +ICM_20948_Status_e ICM_20948::i2cMasterConfigureSlave(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap) +{ + return (i2cControllerConfigurePeripheral(peripheral, addr, reg, len, Rw, enable, data_only, grp, swap, 0)); +} + +ICM_20948_Status_e ICM_20948::i2cControllerPeriph4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + status = ICM_20948_i2c_controller_periph4_txn(&_device, addr, reg, data, len, Rw, send_reg_addr); + return status; +} + +//Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. +//https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ +ICM_20948_Status_e ICM_20948::i2cMasterSLV4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + return (i2cControllerPeriph4Transaction(addr, reg, data, len, Rw, send_reg_addr)); +} + +ICM_20948_Status_e ICM_20948::i2cMasterSingleW(uint8_t addr, uint8_t reg, uint8_t data) +{ + status = ICM_20948_i2c_master_single_w(&_device, addr, reg, &data); + return status; +} +uint8_t ICM_20948::i2cMasterSingleR(uint8_t addr, uint8_t reg) +{ + uint8_t data = 0; + status = ICM_20948_i2c_master_single_r(&_device, addr, reg, &data); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::i2cMasterSingleR: ICM_20948_i2c_master_single_r returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return data; +} + +ICM_20948_Status_e ICM_20948::startupDefault(bool minimal) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + retval = checkID(); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: checkID returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = swReset(); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: swReset returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + delay(50); + + retval = sleep(false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: sleep returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = lowPower(false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: lowPower returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = startupMagnetometer(minimal); // Pass the minimal startup flag to startupMagnetometer + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: startupMagnetometer returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + if (minimal) // Return now if minimal is true + { + debugPrintln(F("ICM_20948::startupDefault: minimal startup complete!")); + return status; + } + + retval = setSampleMode((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Continuous); // options: ICM_20948_Sample_Mode_Continuous or ICM_20948_Sample_Mode_Cycled + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setSampleMode returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } // sensors: ICM_20948_Internal_Acc, ICM_20948_Internal_Gyr, ICM_20948_Internal_Mst + + ICM_20948_fss_t FSS; + FSS.a = gpm2; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + FSS.g = dps250; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + retval = setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), FSS); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setFullScale returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + ICM_20948_dlpcfg_t dlpcfg; + dlpcfg.a = acc_d473bw_n499bw; + dlpcfg.g = gyr_d361bw4_n376bw5; + retval = setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), dlpcfg); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: setDLPFcfg returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = enableDLPF(ICM_20948_Internal_Acc, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: enableDLPF (Acc) returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = enableDLPF(ICM_20948_Internal_Gyr, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupDefault: enableDLPF (Gyr) returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + return status; +} + +// direct read/write +ICM_20948_Status_e ICM_20948::read(uint8_t reg, uint8_t *pdata, uint32_t len) +{ + status = ICM_20948_execute_r(&_device, reg, pdata, len); + return (status); +} + +ICM_20948_Status_e ICM_20948::write(uint8_t reg, uint8_t *pdata, uint32_t len) +{ + status = ICM_20948_execute_w(&_device, reg, pdata, len); + return (status); +} + +uint8_t ICM_20948::readMag(AK09916_Reg_Addr_e reg) +{ + uint8_t data = i2cMasterSingleR(MAG_AK09916_I2C_ADDR, reg); // i2cMasterSingleR updates status too + return data; +} + +ICM_20948_Status_e ICM_20948::writeMag(AK09916_Reg_Addr_e reg, uint8_t *pdata) +{ + status = i2cMasterSingleW(MAG_AK09916_I2C_ADDR, reg, *pdata); + return status; +} + +ICM_20948_Status_e ICM_20948::resetMag() +{ + uint8_t SRST = 1; + // SRST: Soft reset + // “0”: Normal + // “1”: Reset + // When “1” is set, all registers are initialized. After reset, SRST bit turns to “0” automatically. + status = i2cMasterSingleW(MAG_AK09916_I2C_ADDR, AK09916_REG_CNTL3, SRST); + return status; +} + +// FIFO + +ICM_20948_Status_e ICM_20948::enableFIFO(bool enable) +{ + status = ICM_20948_enable_FIFO(&_device, enable); + return status; +} + +ICM_20948_Status_e ICM_20948::resetFIFO(void) +{ + status = ICM_20948_reset_FIFO(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::setFIFOmode(bool snapshot) +{ + // Default to Stream (non-Snapshot) mode + status = ICM_20948_set_FIFO_mode(&_device, snapshot); + return status; +} + +ICM_20948_Status_e ICM_20948::getFIFOcount(uint16_t *count) +{ + status = ICM_20948_get_FIFO_count(&_device, count); + return status; +} + +ICM_20948_Status_e ICM_20948::readFIFO(uint8_t *data, uint8_t len) +{ + status = ICM_20948_read_FIFO(&_device, data, len); + return status; +} + +// DMP + +ICM_20948_Status_e ICM_20948::enableDMP(bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the DMP? + { + status = ICM_20948_enable_DMP(&_device, enable == true ? 1 : 0); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::resetDMP(void) +{ + status = ICM_20948_reset_DMP(&_device); + return status; +} + +ICM_20948_Status_e ICM_20948::loadDMPFirmware(void) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to load the DMP firmware? + { + status = ICM_20948_firmware_load(&_device); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setDMPstartAddress(unsigned short address) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the start address? + { + status = ICM_20948_set_dmp_start_address(&_device, address); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::enableDMPSensor(enum inv_icm20948_sensor sensor, bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the sensor? + { + status = inv_icm20948_enable_dmp_sensor(&_device, sensor, enable == true ? 1 : 0); + debugPrint(F("ICM_20948::enableDMPSensor: _enabled_Android_0: ")); + debugPrintf((int)_device._enabled_Android_0); + debugPrint(F(" _enabled_Android_1: ")); + debugPrintf((int)_device._enabled_Android_1); + debugPrint(F(" _dataOutCtl1: ")); + debugPrintf((int)_device._dataOutCtl1); + debugPrint(F(" _dataOutCtl2: ")); + debugPrintf((int)_device._dataOutCtl2); + debugPrint(F(" _dataRdyStatus: ")); + debugPrintf((int)_device._dataRdyStatus); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::enableDMPSensorInt(enum inv_icm20948_sensor sensor, bool enable) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to enable the sensor interrupt? + { + status = inv_icm20948_enable_dmp_sensor_int(&_device, sensor, enable == true ? 1 : 0); + debugPrint(F("ICM_20948::enableDMPSensorInt: _enabled_Android_intr_0: ")); + debugPrintf((int)_device._enabled_Android_intr_0); + debugPrint(F(" _enabled_Android_intr_1: ")); + debugPrintf((int)_device._enabled_Android_intr_1); + debugPrint(F(" _dataIntrCtl: ")); + debugPrintf((int)_device._dataIntrCtl); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::writeDMPmems(unsigned short reg, unsigned int length, const unsigned char *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to write to the DMP? + { + status = inv_icm20948_write_mems(&_device, reg, length, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::readDMPmems(unsigned short reg, unsigned int length, unsigned char *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to read from the DMP? + { + status = inv_icm20948_read_mems(&_device, reg, length, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setDMPODRrate(enum DMP_ODR_Registers odr_reg, int interval) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the DMP ODR? + { + // In order to set an ODR for a given sensor data, write 2-byte value to DMP using key defined above for a particular sensor. + // Setting value can be calculated as follows: + // Value = (DMP running rate (225Hz) / ODR ) - 1 + // E.g. For a 25Hz ODR rate, value= (225/25) - 1 = 8. + + status = inv_icm20948_set_dmp_sensor_period(&_device, odr_reg, interval); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::readDMPdataFromFIFO(icm_20948_DMP_data_t *data) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the data from the FIFO? + { + status = inv_icm20948_read_dmp_data(&_device, data); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +ICM_20948_Status_e ICM_20948::setGyroSF(unsigned char div, int gyro_level) +{ + if (_device._dmp_firmware_available == true) // Should we attempt to set the Gyro SF? + { + status = inv_icm20948_set_gyro_sf(&_device, div, gyro_level); + debugPrint(F("ICM_20948::setGyroSF: pll: ")); + debugPrintf((int)_device._gyroSFpll); + debugPrint(F(" Gyro SF is: ")); + debugPrintf((int)_device._gyroSF); + debugPrintln(F("")); + return status; + } + return ICM_20948_Stat_DMPNotSupported; +} + +// Combine all of the DMP start-up code from the earlier DMP examples +// This function is defined as __attribute__((weak)) so you can overwrite it if you want to, +// e.g. to modify the sample rate +ICM_20948_Status_e ICM_20948::initializeDMP(void) +{ + // First, let's check if the DMP is available + if (_device._dmp_firmware_available != true) + { + debugPrint(F("ICM_20948::startupDMP: DMP is not available. Please check that you have uncommented line 29 (#define ICM_20948_USE_DMP) in ICM_20948_C.h...")); + return ICM_20948_Stat_DMPNotSupported; + } + + ICM_20948_Status_e worstResult = ICM_20948_Stat_Ok; + +#if defined(ICM_20948_USE_DMP) + + // The ICM-20948 is awake and ready but hasn't been configured. Let's step through the configuration + // sequence from InvenSense's _confidential_ Application Note "Programming Sequence for DMP Hardware Functions". + + ICM_20948_Status_e result = ICM_20948_Stat_Ok; // Use result and worstResult to show if the configuration was successful + + // Normally, when the DMP is not enabled, startupMagnetometer (called by startupDefault, which is called by begin) configures the AK09916 magnetometer + // to run at 100Hz by setting the CNTL2 register (0x31) to 0x08. Then the ICM20948's I2C_SLV0 is configured to read + // nine bytes from the mag every sample, starting from the STATUS1 register (0x10). ST1 includes the DRDY (Data Ready) bit. + // Next are the six magnetometer readings (little endian). After a dummy byte, the STATUS2 register (0x18) contains the HOFL (Overflow) bit. + // + // But looking very closely at the InvenSense example code, we can see in inv_icm20948_resume_akm (in Icm20948AuxCompassAkm.c) that, + // when the DMP is running, the magnetometer is set to Single Measurement (SM) mode and that ten bytes are read, starting from the reserved + // RSV2 register (0x03). The datasheet does not define what registers 0x04 to 0x0C contain. There is definitely some secret sauce in here... + // The magnetometer data appears to be big endian (not little endian like the HX/Y/Z registers) and starts at register 0x04. + // We had to examine the I2C traffic between the master and the AK09916 on the AUX_DA and AUX_CL pins to discover this... + // + // So, we need to set up I2C_SLV0 to do the ten byte reading. The parameters passed to i2cControllerConfigurePeripheral are: + // 0: use I2C_SLV0 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_RSV2: we start reading here (0x03). Secret sauce... + // 10: we read 10 bytes each cycle + // true: set the I2C_SLV0_RNW ReadNotWrite bit so we read the 10 bytes (not write them) + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit to enable reading from the peripheral at the sample rate + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // true: set the I2C_SLV0_CTRL I2C_SLV0_GRP bit to show the register pairing starts at byte 1+2 (copied from inv_icm20948_resume_akm) + // true: set the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW to byte-swap the data from the mag (copied from inv_icm20948_resume_akm) + result = i2cControllerConfigurePeripheral(0, MAG_AK09916_I2C_ADDR, AK09916_REG_RSV2, 10, true, true, false, true, true); if (result > worstResult) worstResult = result; + // + // We also need to set up I2C_SLV1 to do the Single Measurement triggering: + // 1: use I2C_SLV1 + // MAG_AK09916_I2C_ADDR: the I2C address of the AK09916 magnetometer (0x0C unshifted) + // AK09916_REG_CNTL2: we start writing here (0x31) + // 1: not sure why, but the write does not happen if this is set to zero + // false: clear the I2C_SLV0_RNW ReadNotWrite bit so we write the dataOut byte + // true: set the I2C_SLV0_CTRL I2C_SLV0_EN bit. Not sure why, but the write does not happen if this is clear + // false: clear the I2C_SLV0_CTRL I2C_SLV0_REG_DIS (we want to write the register value) + // false: clear the I2C_SLV0_CTRL I2C_SLV0_GRP bit + // false: clear the I2C_SLV0_CTRL I2C_SLV0_BYTE_SW bit + // AK09916_mode_single: tell I2C_SLV1 to write the Single Measurement command each sample + result = i2cControllerConfigurePeripheral(1, MAG_AK09916_I2C_ADDR, AK09916_REG_CNTL2, 1, false, true, false, false, false, AK09916_mode_single); if (result > worstResult) worstResult = result; + + // Set the I2C Master ODR configuration + // It is not clear why we need to do this... But it appears to be essential! From the datasheet: + // "I2C_MST_ODR_CONFIG[3:0]: ODR configuration for external sensor when gyroscope and accelerometer are disabled. + // ODR is computed as follows: 1.1 kHz/(2^((odr_config[3:0])) ) + // When gyroscope is enabled, all sensors (including I2C_MASTER) use the gyroscope ODR. + // If gyroscope is disabled, then all sensors (including I2C_MASTER) use the accelerometer ODR." + // Since both gyro and accel are running, setting this register should have no effect. But it does. Maybe because the Gyro and Accel are placed in Low Power Mode (cycled)? + // You can see by monitoring the Aux I2C pins that the next three lines reduce the bus traffic (magnetometer reads) from 1125Hz to the chosen rate: 68.75Hz in this case. + result = setBank(3); if (result > worstResult) worstResult = result; // Select Bank 3 + uint8_t mstODRconfig = 0x04; // Set the ODR configuration to 1100/2^4 = 68.75Hz + result = write(AGB3_REG_I2C_MST_ODR_CONFIG, &mstODRconfig, 1); if (result > worstResult) worstResult = result; // Write one byte to the I2C_MST_ODR_CONFIG register + + // Configure clock source through PWR_MGMT_1 + // ICM_20948_Clock_Auto selects the best available clock source – PLL if ready, else use the Internal oscillator + result = setClockSource(ICM_20948_Clock_Auto); if (result > worstResult) worstResult = result; // This is shorthand: success will be set to false if setClockSource fails + + // Enable accel and gyro sensors through PWR_MGMT_2 + // Enable Accelerometer (all axes) and Gyroscope (all axes) by writing zero to PWR_MGMT_2 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t pwrMgmt2 = 0x40; // Set the reserved bit 6 (pressure sensor disable?) + result = write(AGB0_REG_PWR_MGMT_2, &pwrMgmt2, 1); if (result > worstResult) worstResult = result; // Write one byte to the PWR_MGMT_2 register + + // Place _only_ I2C_Master in Low Power Mode (cycled) via LP_CONFIG + // The InvenSense Nucleo example initially puts the accel and gyro into low power mode too, but then later updates LP_CONFIG so only the I2C_Master is in Low Power Mode + result = setSampleMode(ICM_20948_Internal_Mst, ICM_20948_Sample_Mode_Cycled); if (result > worstResult) worstResult = result; + + // Disable the FIFO + result = enableFIFO(false); if (result > worstResult) worstResult = result; + + // Disable the DMP + result = enableDMP(false); if (result > worstResult) worstResult = result; + + // Set Gyro FSR (Full scale range) to 2000dps through GYRO_CONFIG_1 + // Set Accel FSR (Full scale range) to 4g through ACCEL_CONFIG + ICM_20948_fss_t myFSS; // This uses a "Full Scale Settings" structure that can contain values for all configurable sensors + myFSS.a = gpm4; // (ICM_20948_ACCEL_CONFIG_FS_SEL_e) + // gpm2 + // gpm4 + // gpm8 + // gpm16 + myFSS.g = dps2000; // (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) + // dps250 + // dps500 + // dps1000 + // dps2000 + result = setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), myFSS); if (result > worstResult) worstResult = result; + + // The InvenSense Nucleo code also enables the gyro DLPF (but leaves GYRO_DLPFCFG set to zero = 196.6Hz (3dB)) + // We found this by going through the SPI data generated by ZaneL's Teensy-ICM-20948 library byte by byte... + // The gyro DLPF is enabled by default (GYRO_CONFIG_1 = 0x01) so the following line should have no effect, but we'll include it anyway + result = enableDLPF(ICM_20948_Internal_Gyr, true); if (result > worstResult) worstResult = result; + + // Enable interrupt for FIFO overflow from FIFOs through INT_ENABLE_2 + // If we see this interrupt, we'll need to reset the FIFO + //result = intEnableOverflowFIFO( 0x1F ); if (result > worstResult) worstResult = result; // Enable the interrupt on all FIFOs + + // Turn off what goes into the FIFO through FIFO_EN_1, FIFO_EN_2 + // Stop the peripheral data from being written to the FIFO by writing zero to FIFO_EN_1 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t zero = 0; + result = write(AGB0_REG_FIFO_EN_1, &zero, 1); if (result > worstResult) worstResult = result; + // Stop the accelerometer, gyro and temperature data from being written to the FIFO by writing zero to FIFO_EN_2 + result = write(AGB0_REG_FIFO_EN_2, &zero, 1); if (result > worstResult) worstResult = result; + + // Turn off data ready interrupt through INT_ENABLE_1 + result = intEnableRawDataReady(false); if (result > worstResult) worstResult = result; + + // Reset FIFO through FIFO_RST + result = resetFIFO(); if (result > worstResult) worstResult = result; + + // Set gyro sample rate divider with GYRO_SMPLRT_DIV + // Set accel sample rate divider with ACCEL_SMPLRT_DIV_2 + ICM_20948_smplrt_t mySmplrt; + mySmplrt.g = 19; // ODR is computed as follows: 1.1 kHz/(1+GYRO_SMPLRT_DIV[7:0]). 19 = 55Hz. InvenSense Nucleo example uses 19 (0x13). + mySmplrt.a = 19; // ODR is computed as follows: 1.125 kHz/(1+ACCEL_SMPLRT_DIV[11:0]). 19 = 56.25Hz. InvenSense Nucleo example uses 19 (0x13). + //mySmplrt.g = 4; // 225Hz + //mySmplrt.a = 4; // 225Hz + //mySmplrt.g = 8; // 112Hz + //mySmplrt.a = 8; // 112Hz + result = setSampleRate((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), mySmplrt); if (result > worstResult) worstResult = result; + + // Setup DMP start address through PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Now load the DMP firmware + result = loadDMPFirmware(); if (result > worstResult) worstResult = result; + + // Write the 2 byte Firmware Start Value to ICM PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + result = setDMPstartAddress(); if (result > worstResult) worstResult = result; // Defaults to DMP_START_ADDRESS + + // Set the Hardware Fix Disable register to 0x48 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fix = 0x48; + result = write(AGB0_REG_HW_FIX_DISABLE, &fix, 1); if (result > worstResult) worstResult = result; + + // Set the Single FIFO Priority Select register to 0xE4 + result = setBank(0); if (result > worstResult) worstResult = result; // Select Bank 0 + uint8_t fifoPrio = 0xE4; + result = write(AGB0_REG_SINGLE_FIFO_PRIORITY_SEL, &fifoPrio, 1); if (result > worstResult) worstResult = result; + + // Configure Accel scaling to DMP + // The DMP scales accel raw data internally to align 1g as 2^25 + // In order to align internal accel raw data 2^25 = 1g write 0x04000000 when FSR is 4g + const unsigned char accScale[4] = {0x04, 0x00, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE, 4, &accScale[0]); if (result > worstResult) worstResult = result; // Write accScale to ACC_SCALE DMP register + // In order to output hardware unit data as configured FSR write 0x00040000 when FSR is 4g + const unsigned char accScale2[4] = {0x00, 0x04, 0x00, 0x00}; + result = writeDMPmems(ACC_SCALE2, 4, &accScale2[0]); if (result > worstResult) worstResult = result; // Write accScale2 to ACC_SCALE2 DMP register + + // Configure Compass mount matrix and scale to DMP + // The mount matrix write to DMP register is used to align the compass axes with accel/gyro. + // This mechanism is also used to convert hardware unit to uT. The value is expressed as 1uT = 2^30. + // Each compass axis will be converted as below: + // X = raw_x * CPASS_MTX_00 + raw_y * CPASS_MTX_01 + raw_z * CPASS_MTX_02 + // Y = raw_x * CPASS_MTX_10 + raw_y * CPASS_MTX_11 + raw_z * CPASS_MTX_12 + // Z = raw_x * CPASS_MTX_20 + raw_y * CPASS_MTX_21 + raw_z * CPASS_MTX_22 + // The AK09916 produces a 16-bit signed output in the range +/-32752 corresponding to +/-4912uT. 1uT = 6.66 ADU. + // 2^30 / 6.66666 = 161061273 = 0x9999999 + const unsigned char mountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char mountMultiplierPlus[4] = {0x09, 0x99, 0x99, 0x99}; // Value taken from InvenSense Nucleo example + const unsigned char mountMultiplierMinus[4] = {0xF6, 0x66, 0x66, 0x67}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(CPASS_MTX_00, 4, &mountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_01, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_02, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_10, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_11, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_12, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_20, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_21, 4, &mountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(CPASS_MTX_22, 4, &mountMultiplierMinus[0]); if (result > worstResult) worstResult = result; + + // Configure the B2S Mounting Matrix + const unsigned char b2sMountMultiplierZero[4] = {0x00, 0x00, 0x00, 0x00}; + const unsigned char b2sMountMultiplierPlus[4] = {0x40, 0x00, 0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(B2S_MTX_00, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_01, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_02, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_10, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_11, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_12, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_20, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_21, 4, &b2sMountMultiplierZero[0]); if (result > worstResult) worstResult = result; + result = writeDMPmems(B2S_MTX_22, 4, &b2sMountMultiplierPlus[0]); if (result > worstResult) worstResult = result; + + // Configure the DMP Gyro Scaling Factor + // @param[in] gyro_div Value written to GYRO_SMPLRT_DIV register, where + // 0=1125Hz sample rate, 1=562.5Hz sample rate, ... 4=225Hz sample rate, ... + // 10=102.2727Hz sample rate, ... etc. + // @param[in] gyro_level 0=250 dps, 1=500 dps, 2=1000 dps, 3=2000 dps + result = setGyroSF(19, 3); if (result > worstResult) worstResult = result; // 19 = 55Hz (see above), 3 = 2000dps (see above) + + // Configure the Gyro full scale + // 2000dps : 2^28 + // 1000dps : 2^27 + // 500dps : 2^26 + // 250dps : 2^25 + const unsigned char gyroFullScale[4] = {0x10, 0x00, 0x00, 0x00}; // 2000dps : 2^28 + result = writeDMPmems(GYRO_FULLSCALE, 4, &gyroFullScale[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Only Gain: 15252014 (225Hz) 30504029 (112Hz) 61117001 (56Hz) + const unsigned char accelOnlyGain[4] = {0x03, 0xA4, 0x92, 0x49}; // 56Hz + //const unsigned char accelOnlyGain[4] = {0x00, 0xE8, 0xBA, 0x2E}; // 225Hz + //const unsigned char accelOnlyGain[4] = {0x01, 0xD1, 0x74, 0x5D}; // 112Hz + result = writeDMPmems(ACCEL_ONLY_GAIN, 4, &accelOnlyGain[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Alpha Var: 1026019965 (225Hz) 977872018 (112Hz) 882002213 (56Hz) + const unsigned char accelAlphaVar[4] = {0x34, 0x92, 0x49, 0x25}; // 56Hz + //const unsigned char accelAlphaVar[4] = {0x3D, 0x27, 0xD2, 0x7D}; // 225Hz + //const unsigned char accelAlphaVar[4] = {0x3A, 0x49, 0x24, 0x92}; // 112Hz + result = writeDMPmems(ACCEL_ALPHA_VAR, 4, &accelAlphaVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel A Var: 47721859 (225Hz) 95869806 (112Hz) 191739611 (56Hz) + const unsigned char accelAVar[4] = {0x0B, 0x6D, 0xB6, 0xDB}; // 56Hz + //const unsigned char accelAVar[4] = {0x02, 0xD8, 0x2D, 0x83}; // 225Hz + //const unsigned char accelAVar[4] = {0x05, 0xB6, 0xDB, 0x6E}; // 112Hz + result = writeDMPmems(ACCEL_A_VAR, 4, &accelAVar[0]); if (result > worstResult) worstResult = result; + + // Configure the Accel Cal Rate + const unsigned char accelCalRate[4] = {0x00, 0x00}; // Value taken from InvenSense Nucleo example + result = writeDMPmems(ACCEL_CAL_RATE, 2, &accelCalRate[0]); if (result > worstResult) worstResult = result; + + // Configure the Compass Time Buffer. The I2C Master ODR Configuration (see above) sets the magnetometer read rate to 68.75Hz. + // Let's set the Compass Time Buffer to 69 (Hz). + const unsigned char compassRate[2] = {0x00, 0x45}; // 69Hz + result = writeDMPmems(CPASS_TIME_BUFFER, 2, &compassRate[0]); if (result > worstResult) worstResult = result; + + // Enable DMP interrupt + // This would be the most efficient way of getting the DMP data, instead of polling the FIFO + //result = intEnableDMP(true); if (result > worstResult) worstResult = result; + +#endif + + return worstResult; +} + +// I2C +ICM_20948_I2C::ICM_20948_I2C() +{ +} + +ICM_20948_Status_e ICM_20948_I2C::begin(TwoWire &wirePort, bool ad0val, uint8_t ad0pin) +{ + // Associate + _ad0 = ad0pin; + _i2c = &wirePort; + _ad0val = ad0val; + + _addr = ICM_20948_I2C_ADDR_AD0; + if (_ad0val) + { + _addr = ICM_20948_I2C_ADDR_AD1; + } + + // Set pinmodes + if (_ad0 != ICM_20948_ARD_UNUSED_PIN) + { + pinMode(_ad0, OUTPUT); + } + + // Set pins to default positions + if (_ad0 != ICM_20948_ARD_UNUSED_PIN) + { + digitalWrite(_ad0, _ad0val); + } + + // _i2c->begin(); // Moved into user's sketch + + // Set up the serif + _serif.write = ICM_20948_write_I2C; + _serif.read = ICM_20948_read_I2C; + _serif.user = (void *)this; // refer to yourself in the user field + + // Link the serif + _device._serif = &_serif; + +#if defined(ICM_20948_USE_DMP) + _device._dmp_firmware_available = true; // Initialize _dmp_firmware_available +#else + _device._dmp_firmware_available = false; // Initialize _dmp_firmware_available +#endif + + _device._firmware_loaded = false; // Initialize _firmware_loaded + _device._last_bank = 255; // Initialize _last_bank. Make it invalid. It will be set by the first call of ICM_20948_set_bank. + _device._last_mems_bank = 255; // Initialize _last_mems_bank. Make it invalid. It will be set by the first call of inv_icm20948_write_mems. + _device._gyroSF = 0; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + _device._gyroSFpll = 0; + _device._enabled_Android_0 = 0; // Keep track of which Android sensors are enabled: 0-31 + _device._enabled_Android_1 = 0; // Keep track of which Android sensors are enabled: 32- + _device._enabled_Android_intr_0 = 0; // Keep track of which Android sensor interrupts are enabled: 0-31 + _device._enabled_Android_intr_1 = 0; // Keep track of which Android sensor interrupts are enabled: 32- + + // Perform default startup + // Do a minimal startupDefault if using the DMP. User can always call startupDefault(false) manually if required. + status = startupDefault(_device._dmp_firmware_available); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948_I2C::begin: startupDefault returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + return status; +} + +ICM_20948_Status_e ICM_20948::startupMagnetometer(bool minimal) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + i2cMasterPassthrough(false); //Do not connect the SDA/SCL pins to AUX_DA/AUX_CL + i2cMasterEnable(true); + + resetMag(); + + //After a ICM reset the Mag sensor may stop responding over the I2C master + //Reset the Master I2C until it responds + uint8_t tries = 0; + while (tries < MAX_MAGNETOMETER_STARTS) + { + tries++; + + //See if we can read the WhoIAm register correctly + retval = magWhoIAm(); + if (retval == ICM_20948_Stat_Ok) + break; //WIA matched! + + i2cMasterReset(); //Otherwise, reset the master I2C and try again + + delay(10); + } + + if (tries == MAX_MAGNETOMETER_STARTS) + { + debugPrint(F("ICM_20948::startupMagnetometer: reached MAX_MAGNETOMETER_STARTS (")); + debugPrintf((int)MAX_MAGNETOMETER_STARTS); + debugPrintln(F("). Returning ICM_20948_Stat_WrongID")); + status = ICM_20948_Stat_WrongID; + return status; + } + else + { + debugPrint(F("ICM_20948::startupMagnetometer: successful magWhoIAm after ")); + debugPrintf((int)tries); + if (tries == 1) + debugPrintln(F(" try")); + else + debugPrintln(F(" tries")); + } + + //Return now if minimal is true. The mag will be configured manually for the DMP + if (minimal) // Return now if minimal is true + { + debugPrintln(F("ICM_20948::startupMagnetometer: minimal startup complete!")); + return status; + } + + //Set up magnetometer + AK09916_CNTL2_Reg_t reg; + reg.MODE = AK09916_mode_cont_100hz; + reg.reserved_0 = 0; // Make sure the unused bits are clear. Probably redundant, but prevents confusion when looking at the I2C traffic + retval = writeMag(AK09916_REG_CNTL2, (uint8_t *)®); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupMagnetometer: writeMag returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + retval = i2cControllerConfigurePeripheral(0, MAG_AK09916_I2C_ADDR, AK09916_REG_ST1, 9, true, true, false, false, false); + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::startupMagnetometer: i2cMasterConfigurePeripheral returned: ")); + debugPrintStatus(retval); + debugPrintln(F("")); + status = retval; + return status; + } + + return status; +} + +ICM_20948_Status_e ICM_20948::magWhoIAm(void) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + uint8_t whoiam1, whoiam2; + whoiam1 = readMag(AK09916_REG_WIA1); + // readMag calls i2cMasterSingleR which calls ICM_20948_i2c_master_single_r + // i2cMasterSingleR updates status so it is OK to set retval to status here + retval = status; + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) readMag set status to: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return retval; + } + whoiam2 = readMag(AK09916_REG_WIA2); + // readMag calls i2cMasterSingleR which calls ICM_20948_i2c_master_single_r + // i2cMasterSingleR updates status so it is OK to set retval to status here + retval = status; + if (retval != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) whoiam2: ")); + debugPrintf((int)whoiam2); + debugPrint(F(" (should be 9) readMag set status to: ")); + debugPrintStatus(status); + debugPrintln(F("")); + return retval; + } + + if ((whoiam1 == (MAG_AK09916_WHO_AM_I >> 8)) && (whoiam2 == (MAG_AK09916_WHO_AM_I & 0xFF))) + { + retval = ICM_20948_Stat_Ok; + status = retval; + return status; + } + + debugPrint(F("ICM_20948::magWhoIAm: whoiam1: ")); + debugPrintf((int)whoiam1); + debugPrint(F(" (should be 72) whoiam2: ")); + debugPrintf((int)whoiam2); + debugPrintln(F(" (should be 9). Returning ICM_20948_Stat_WrongID")); + + retval = ICM_20948_Stat_WrongID; + status = retval; + return status; +} + +// SPI + +// SPISettings ICM_20948_SPI_DEFAULT_SETTINGS(ICM_20948_SPI_DEFAULT_FREQ, ICM_20948_SPI_DEFAULT_ORDER, ICM_20948_SPI_DEFAULT_MODE); + +ICM_20948_SPI::ICM_20948_SPI() +{ +} + +ICM_20948_Status_e ICM_20948_SPI::begin(uint8_t csPin, SPIClass &spiPort, uint32_t SPIFreq) +{ + if (SPIFreq > 7000000) + SPIFreq = 7000000; // Limit SPI frequency to 7MHz + + // Associate + _spi = &spiPort; + _spisettings = SPISettings(SPIFreq, ICM_20948_SPI_DEFAULT_ORDER, ICM_20948_SPI_DEFAULT_MODE); + _cs = csPin; + + // Set pinmodes + pinMode(_cs, OUTPUT); + + // Set pins to default positions + digitalWrite(_cs, HIGH); + + // _spi->begin(); // Moved into user's sketch + + // 'Kickstart' the SPI hardware. + _spi->beginTransaction(_spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + // Set up the serif + _serif.write = ICM_20948_write_SPI; + _serif.read = ICM_20948_read_SPI; + _serif.user = (void *)this; // refer to yourself in the user field + + // Link the serif + _device._serif = &_serif; + +#if defined(ICM_20948_USE_DMP) + _device._dmp_firmware_available = true; // Initialize _dmp_firmware_available +#else + _device._dmp_firmware_available = false; // Initialize _dmp_firmware_available +#endif + + _device._firmware_loaded = false; // Initialize _firmware_loaded + _device._last_bank = 255; // Initialize _last_bank. Make it invalid. It will be set by the first call of ICM_20948_set_bank. + _device._last_mems_bank = 255; // Initialize _last_mems_bank. Make it invalid. It will be set by the first call of inv_icm20948_write_mems. + _device._gyroSF = 0; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + _device._gyroSFpll = 0; + _device._enabled_Android_0 = 0; // Keep track of which Android sensors are enabled: 0-31 + _device._enabled_Android_1 = 0; // Keep track of which Android sensors are enabled: 32- + _device._enabled_Android_intr_0 = 0; // Keep track of which Android sensor interrupts are enabled: 0-31 + _device._enabled_Android_intr_1 = 0; // Keep track of which Android sensor interrupts are enabled: 32- + + // Perform default startup + // Do a minimal startupDefault if using the DMP. User can always call startupDefault(false) manually if required. + status = startupDefault(_device._dmp_firmware_available); + if (status != ICM_20948_Stat_Ok) + { + debugPrint(F("ICM_20948_SPI::begin: startupDefault returned: ")); + debugPrintStatus(status); + debugPrintln(F("")); + } + + return status; +} + +// serif functions for the I2C and SPI classes +ICM_20948_Status_e ICM_20948_write_I2C(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + TwoWire *_i2c = ((ICM_20948_I2C *)user)->_i2c; // Cast user field to ICM_20948_I2C type and extract the I2C interface pointer + uint8_t addr = ((ICM_20948_I2C *)user)->_addr; + if (_i2c == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + _i2c->beginTransmission(addr); + _i2c->write(reg); + _i2c->write(data, (uint8_t)len); + _i2c->endTransmission(); + + // for( uint32_t indi = 0; indi < len; indi++ ){ + // _i2c->beginTransmission(addr); + // _i2c->write(reg + indi); + // _i2c->write(*(data + indi) ); + // _i2c->endTransmission(); + // delay(10); + // } + + // delay(10); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_read_I2C(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + TwoWire *_i2c = ((ICM_20948_I2C *)user)->_i2c; + uint8_t addr = ((ICM_20948_I2C *)user)->_addr; + if (_i2c == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + _i2c->beginTransmission(addr); + _i2c->write(reg); + _i2c->endTransmission(false); // Send repeated start + + uint32_t offset = 0; + uint32_t num_received = _i2c->requestFrom(addr, len); + // while(_i2c->available()){ + // if(len > 0){ + // *(buff + offset) = _i2c->read(); + // len--; + // }else{ + // break; + // } + // } + + if (num_received == len) + { + for (uint8_t i = 0; i < len; i++) + { + buff[i] = _i2c->read(); + } + return ICM_20948_Stat_Ok; + } + else + { + return ICM_20948_Stat_NoData; + } + + if (len != 0) + { + return ICM_20948_Stat_NoData; + } + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_write_SPI(uint8_t reg, uint8_t *data, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + SPIClass *_spi = ((ICM_20948_SPI *)user)->_spi; // Cast user field to ICM_20948_SPI type and extract the SPI interface pointer + uint8_t cs = ((ICM_20948_SPI *)user)->_cs; + SPISettings spisettings = ((ICM_20948_SPI *)user)->_spisettings; + if (_spi == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + // 'Kickstart' the SPI hardware. This is a fairly high amount of overhead, but it guarantees that the lines will start in the correct states even when sharing the SPI bus with devices that use other modes + _spi->beginTransaction(spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + _spi->beginTransaction(spisettings); + digitalWrite(cs, LOW); + // delayMicroseconds(5); + _spi->transfer(((reg & 0x7F) | 0x00)); + // SPI.transfer(data, len); // Can't do this thanks to Arduino's poor implementation + for (uint32_t indi = 0; indi < len; indi++) + { + _spi->transfer(*(data + indi)); + } + // delayMicroseconds(5); + digitalWrite(cs, HIGH); + _spi->endTransaction(); + + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_read_SPI(uint8_t reg, uint8_t *buff, uint32_t len, void *user) +{ + if (user == NULL) + { + return ICM_20948_Stat_ParamErr; + } + SPIClass *_spi = ((ICM_20948_SPI *)user)->_spi; + uint8_t cs = ((ICM_20948_SPI *)user)->_cs; + SPISettings spisettings = ((ICM_20948_SPI *)user)->_spisettings; + if (_spi == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + // 'Kickstart' the SPI hardware. This is a fairly high amount of overhead, but it guarantees that the lines will start in the correct states + _spi->beginTransaction(spisettings); + _spi->transfer(0x00); + _spi->endTransaction(); + + _spi->beginTransaction(spisettings); + digitalWrite(cs, LOW); + // delayMicroseconds(5); + _spi->transfer(((reg & 0x7F) | 0x80)); + // SPI.transfer(data, len); // Can't do this thanks to Arduino's stupid implementation + for (uint32_t indi = 0; indi < len; indi++) + { + *(buff + indi) = _spi->transfer(0x00); + } + // delayMicroseconds(5); + digitalWrite(cs, HIGH); + _spi->endTransaction(); + + return ICM_20948_Stat_Ok; +} diff --git a/lib/ICM-20948/src/ICM_20948.h b/lib/ICM-20948/src/ICM_20948.h new file mode 100644 index 0000000..4eb62e1 --- /dev/null +++ b/lib/ICM-20948/src/ICM_20948.h @@ -0,0 +1,264 @@ +/* + +A C++ interface to the ICM-20948 + +*/ + +#ifndef _ICM_20948_H_ +#define _ICM_20948_H_ + +#include "util/ICM_20948_C.h" // The C backbone. ICM_20948_USE_DMP is defined in here. +#include "util/AK09916_REGISTERS.h" + +#include "Arduino.h" // Arduino support +#include "Wire.h" +#include "SPI.h" + +#define ICM_20948_ARD_UNUSED_PIN 0xFF + +// Base +class ICM_20948 +{ +private: + Stream *_debugSerial; //The stream to send debug messages to if enabled + bool _printDebug = false; //Flag to print the serial commands we are sending to the Serial port for debug + + const uint8_t MAX_MAGNETOMETER_STARTS = 10; // This replaces maxTries + +protected: + ICM_20948_Device_t _device; + + float getTempC(int16_t val); + float getGyrDPS(int16_t axis_val); + float getAccMG(int16_t axis_val); + float getMagUT(int16_t axis_val); + +public: + ICM_20948(); // Constructor + +// Enable debug messages using the chosen Serial port (Stream) +// Boards like the RedBoard Turbo use SerialUSB (not Serial). +// But other boards like the SAMD51 Thing Plus use Serial (not SerialUSB). +// These lines let the code compile cleanly on as many SAMD boards as possible. +#if defined(ARDUINO_ARCH_SAMD) // Is this a SAMD board? +#if defined(USB_VID) // Is the USB Vendor ID defined? +#if (USB_VID == 0x1B4F) // Is this a SparkFun board? +#if !defined(ARDUINO_SAMD51_THING_PLUS) & !defined(ARDUINO_SAMD51_MICROMOD) // If it is not a SAMD51 Thing Plus or SAMD51 MicroMod + void enableDebugging(Stream &debugPort = SerialUSB); //Given a port to print to, enable debug messages. +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif +#else + void enableDebugging(Stream &debugPort = Serial); //Given a port to print to, enable debug messages. +#endif + + void disableDebugging(void); //Turn off debug statements + + void debugPrintStatus(ICM_20948_Status_e stat); + + // gfvalvo's flash string helper code: https://forum.arduino.cc/index.php?topic=533118.msg3634809#msg3634809 + void debugPrint(const char *); + void debugPrint(const __FlashStringHelper *); + void debugPrintln(const char *); + void debugPrintln(const __FlashStringHelper *); + void doDebugPrint(char (*)(const char *), const char *, bool newLine = false); + + void debugPrintf(int i); + void debugPrintf(float f); + + ICM_20948_AGMT_t agmt; // Acceleometer, Gyroscope, Magenetometer, and Temperature data + ICM_20948_AGMT_t getAGMT(void); // Updates the agmt field in the object and also returns a copy directly + + float magX(void); // micro teslas + float magY(void); // micro teslas + float magZ(void); // micro teslas + + float accX(void); // milli g's + float accY(void); // milli g's + float accZ(void); // milli g's + + float gyrX(void); // degrees per second + float gyrY(void); // degrees per second + float gyrZ(void); // degrees per second + + float temp(void); // degrees celsius + + ICM_20948_Status_e status; // Status from latest operation + const char *statusString(ICM_20948_Status_e stat = ICM_20948_Stat_NUM); // Returns a human-readable status message. Defaults to status member, but prints string for supplied status if supplied + + // Device Level + ICM_20948_Status_e setBank(uint8_t bank); // Sets the bank + ICM_20948_Status_e swReset(void); // Performs a SW reset + ICM_20948_Status_e sleep(bool on = false); // Set sleep mode for the chip + ICM_20948_Status_e lowPower(bool on = true); // Set low power mode for the chip + ICM_20948_Status_e setClockSource(ICM_20948_PWR_MGMT_1_CLKSEL_e source); // Choose clock source + ICM_20948_Status_e checkID(void); // Return 'ICM_20948_Stat_Ok' if whoami matches ICM_20948_WHOAMI + + bool dataReady(void); // Returns 'true' if data is ready + uint8_t getWhoAmI(void); // Return whoami in out prarmeter + bool isConnected(void); // Returns true if communications with the device are sucessful + + // Internal Sensor Options + ICM_20948_Status_e setSampleMode(uint8_t sensor_id_bm, uint8_t lp_config_cycle_mode); // Use to set accel, gyro, and I2C master into cycled or continuous modes + ICM_20948_Status_e setFullScale(uint8_t sensor_id_bm, ICM_20948_fss_t fss); + ICM_20948_Status_e setDLPFcfg(uint8_t sensor_id_bm, ICM_20948_dlpcfg_t cfg); + ICM_20948_Status_e enableDLPF(uint8_t sensor_id_bm, bool enable); + ICM_20948_Status_e setSampleRate(uint8_t sensor_id_bm, ICM_20948_smplrt_t smplrt); + + // Interrupts on INT and FSYNC Pins + ICM_20948_Status_e clearInterrupts(void); + + ICM_20948_Status_e cfgIntActiveLow(bool active_low); + ICM_20948_Status_e cfgIntOpenDrain(bool open_drain); + ICM_20948_Status_e cfgIntLatch(bool latching); // If not latching then the interrupt is a 50 us pulse + ICM_20948_Status_e cfgIntAnyReadToClear(bool enabled); // If enabled, *ANY* read will clear the INT_STATUS register. So if you have multiple interrupt sources enabled be sure to read INT_STATUS first + ICM_20948_Status_e cfgFsyncActiveLow(bool active_low); + ICM_20948_Status_e cfgFsyncIntMode(bool interrupt_mode); // Can use FSYNC as an interrupt input that sets the I2C Master Status register's PASS_THROUGH bit + + ICM_20948_Status_e intEnableI2C(bool enable); + ICM_20948_Status_e intEnableDMP(bool enable); + ICM_20948_Status_e intEnablePLL(bool enable); + ICM_20948_Status_e intEnableWOM(bool enable); + ICM_20948_Status_e intEnableWOF(bool enable); + ICM_20948_Status_e intEnableRawDataReady(bool enable); + ICM_20948_Status_e intEnableOverflowFIFO(uint8_t bm_enable); + ICM_20948_Status_e intEnableWatermarkFIFO(uint8_t bm_enable); + + ICM_20948_Status_e WOMThreshold(uint8_t threshold); + + // Interface Options + ICM_20948_Status_e i2cMasterPassthrough(bool passthrough = true); + ICM_20948_Status_e i2cMasterEnable(bool enable = true); + ICM_20948_Status_e i2cMasterReset(); + + //Used for configuring peripherals 0-3 + ICM_20948_Status_e i2cControllerConfigurePeripheral(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw = true, bool enable = true, bool data_only = false, bool grp = false, bool swap = false, uint8_t dataOut = 0); + ICM_20948_Status_e i2cControllerPeriph4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr = true); + + //Provided for backward-compatibility only. Please update to i2cControllerConfigurePeripheral and i2cControllerPeriph4Transaction. + //https://www.oshwa.org/2020/06/29/a-resolution-to-redefine-spi-pin-names/ + ICM_20948_Status_e i2cMasterConfigureSlave(uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw = true, bool enable = true, bool data_only = false, bool grp = false, bool swap = false); + ICM_20948_Status_e i2cMasterSLV4Transaction(uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr = true); + + //Used for configuring the Magnetometer + ICM_20948_Status_e i2cMasterSingleW(uint8_t addr, uint8_t reg, uint8_t data); + uint8_t i2cMasterSingleR(uint8_t addr, uint8_t reg); + + // Default Setup + ICM_20948_Status_e startupDefault(bool minimal = false); // If minimal is true, several startup steps are skipped. If ICM_20948_USE_DMP is defined, .begin will call startupDefault with minimal set to true. + + // direct read/write + ICM_20948_Status_e read(uint8_t reg, uint8_t *pdata, uint32_t len); + ICM_20948_Status_e write(uint8_t reg, uint8_t *pdata, uint32_t len); + + //Mag specific + ICM_20948_Status_e startupMagnetometer(bool minimal = false); // If minimal is true, several startup steps are skipped. The mag then needs to be set up manually for the DMP. + ICM_20948_Status_e magWhoIAm(void); + uint8_t readMag(AK09916_Reg_Addr_e reg); + ICM_20948_Status_e writeMag(AK09916_Reg_Addr_e reg, uint8_t *pdata); + ICM_20948_Status_e resetMag(); + + //FIFO + ICM_20948_Status_e enableFIFO(bool enable = true); + ICM_20948_Status_e resetFIFO(void); + ICM_20948_Status_e setFIFOmode(bool snapshot = false); // Default to Stream (non-Snapshot) mode + ICM_20948_Status_e getFIFOcount(uint16_t *count); + ICM_20948_Status_e readFIFO(uint8_t *data, uint8_t len = 1); + + //DMP + + // Done: + // Configure DMP start address through PRGM_STRT_ADDRH/PRGM_STRT_ADDRL + // Load Firmware + // Configure Accel scaling to DMP + // Configure Compass mount matrix and scale to DMP + // Reset FIFO + // Reset DMP + // Enable DMP interrupt + // Configuring DMP to output data to FIFO: set DATA_OUT_CTL1, DATA_OUT_CTL2, DATA_INTR_CTL and MOTION_EVENT_CTL + // Configuring DMP to output data at multiple ODRs + // Configure DATA_RDY_STATUS + // Configuring Accel calibration + // Configuring Compass calibration + // Configuring Gyro gain + // Configuring Accel gain + // Configure I2C_SLV0 and I2C_SLV1 to: request mag data from the hidden reserved AK09916 registers; trigger Single Measurements + // Configure I2C Master ODR (default to 68.75Hz) + + // To Do: + // Additional FIFO output control: FIFO_WATERMARK, BM_BATCH_MASK, BM_BATCH_CNTR, BM_BATCH_THLD + // Configuring DMP features: PED_STD_STEPCTR, PED_STD_TIMECTR + // Enabling Activity Recognition (BAC) feature + // Enabling Significant Motion Detect (SMD) feature + // Enabling Tilt Detector feature + // Enabling Pick Up Gesture feature + // Enabling Fsync detection feature + // Biases: add save and load methods + + ICM_20948_Status_e enableDMP(bool enable = true); + ICM_20948_Status_e resetDMP(void); + ICM_20948_Status_e loadDMPFirmware(void); + ICM_20948_Status_e setDMPstartAddress(unsigned short address = DMP_START_ADDRESS); + ICM_20948_Status_e enableDMPSensor(enum inv_icm20948_sensor sensor, bool enable = true); + ICM_20948_Status_e enableDMPSensorInt(enum inv_icm20948_sensor sensor, bool enable = true); + ICM_20948_Status_e writeDMPmems(unsigned short reg, unsigned int length, const unsigned char *data); + ICM_20948_Status_e readDMPmems(unsigned short reg, unsigned int length, unsigned char *data); + ICM_20948_Status_e setDMPODRrate(enum DMP_ODR_Registers odr_reg, int interval); + ICM_20948_Status_e readDMPdataFromFIFO(icm_20948_DMP_data_t *data); + ICM_20948_Status_e setGyroSF(unsigned char div, int gyro_level); + ICM_20948_Status_e initializeDMP(void) __attribute__((weak)); // Combine all of the DMP start-up code in one place. Can be overwritten if required +}; + +// I2C + +// Forward declarations of TwoWire and Wire for board/variant combinations that don't have a default 'SPI' +//class TwoWire; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE +//extern TwoWire Wire; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE + +class ICM_20948_I2C : public ICM_20948 +{ +private: +protected: +public: + TwoWire *_i2c; + uint8_t _addr; + uint8_t _ad0; + bool _ad0val; + ICM_20948_Serif_t _serif; + + ICM_20948_I2C(); // Constructor + + virtual ICM_20948_Status_e begin(TwoWire &wirePort = Wire, bool ad0val = true, uint8_t ad0pin = ICM_20948_ARD_UNUSED_PIN); +}; + +// SPI +#define ICM_20948_SPI_DEFAULT_FREQ 4000000 +#define ICM_20948_SPI_DEFAULT_ORDER MSBFIRST +#define ICM_20948_SPI_DEFAULT_MODE SPI_MODE0 + +// Forward declarations of SPIClass and SPI for board/variant combinations that don't have a default 'SPI' +//class SPIClass; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE +//extern SPIClass SPI; // Commented by PaulZC 21/2/8 - this was causing compilation to fail on the Arduino NANO 33 BLE + +class ICM_20948_SPI : public ICM_20948 +{ +private: +protected: +public: + SPIClass *_spi; + SPISettings _spisettings; + uint8_t _cs; + ICM_20948_Serif_t _serif; + + ICM_20948_SPI(); // Constructor + + ICM_20948_Status_e begin(uint8_t csPin, SPIClass &spiPort = SPI, uint32_t SPIFreq = ICM_20948_SPI_DEFAULT_FREQ); +}; + +#endif /* _ICM_20948_H_ */ diff --git a/lib/ICM-20948/src/util/AK09916_ENUMERATIONS.h b/lib/ICM-20948/src/util/AK09916_ENUMERATIONS.h new file mode 100644 index 0000000..b62b7c3 --- /dev/null +++ b/lib/ICM-20948/src/util/AK09916_ENUMERATIONS.h @@ -0,0 +1,15 @@ +#ifndef _AK09916_ENUMERATIONS_H_ +#define _AK09916_ENUMERATIONS_H_ + +typedef enum +{ + AK09916_mode_power_down = 0x00, + AK09916_mode_single = (0x01 << 0), + AK09916_mode_cont_10hz = (0x01 << 1), + AK09916_mode_cont_20hz = (0x02 << 1), + AK09916_mode_cont_50hz = (0x03 << 1), + AK09916_mode_cont_100hz = (0x04 << 1), + AK09916_mode_self_test = (0x01 << 4), +} AK09916_mode_e; + +#endif // _AK09916_ENUMERATIONS_H_ \ No newline at end of file diff --git a/lib/ICM-20948/src/util/AK09916_REGISTERS.h b/lib/ICM-20948/src/util/AK09916_REGISTERS.h new file mode 100644 index 0000000..9c91c3c --- /dev/null +++ b/lib/ICM-20948/src/util/AK09916_REGISTERS.h @@ -0,0 +1,83 @@ +#ifndef _AK09916_REGISTERS_H_ +#define _AK09916_REGISTERS_H_ + +#include + +typedef enum +{ + AK09916_REG_WIA1 = 0x00, + AK09916_REG_WIA2, + AK09916_REG_RSV1, + AK09916_REG_RSV2, // Reserved register. We start reading here when using the DMP. Secret sauce... + // discontinuity - containing another nine reserved registers? Secret sauce... + AK09916_REG_ST1 = 0x10, + AK09916_REG_HXL, + AK09916_REG_HXH, + AK09916_REG_HYL, + AK09916_REG_HYH, + AK09916_REG_HZL, + AK09916_REG_HZH, + // discontinuity + AK09916_REG_ST2 = 0x18, + // discontinuity + AK09916_REG_CNTL2 = 0x31, + AK09916_REG_CNTL3, +} AK09916_Reg_Addr_e; + +typedef struct +{ + uint8_t WIA1; +} AK09916_WIA1_Reg_t; + +typedef struct +{ + uint8_t WIA2; +} AK09916_WIA2_Reg_t; + +typedef struct +{ + uint8_t DRDY : 1; + uint8_t DOR : 1; + uint8_t reserved_0 : 6; +} AK09916_ST1_Reg_t; + +// typedef struct{ + +// }AK09916_HXL_Reg_t; + +// typedef struct{ + +// }AK09916_HXH_Reg_t; +// typedef struct{ + +// }AK09916_HYL_Reg_t; +// typedef struct{ + +// }AK09916_HYH_Reg_t; +// typedef struct{ + +// }AK09916_HZL_Reg_t; +// typedef struct{ + +// }AK09916_HZH_Reg_t; + +typedef struct +{ + uint8_t reserved_0 : 3; + uint8_t HOFL : 1; + uint8_t reserved_1 : 4; +} AK09916_ST2_Reg_t; + +typedef struct +{ + uint8_t MODE : 5; + uint8_t reserved_0 : 3; +} AK09916_CNTL2_Reg_t; + +typedef struct +{ + uint8_t SRST : 1; + uint8_t reserved_0 : 7; +} AK09916_CNTL3_Reg_t; + +#endif // _AK09916_REGISTERS_H_ diff --git a/lib/ICM-20948/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 b/lib/ICM-20948/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 new file mode 100644 index 0000000..ca0dd48 --- /dev/null +++ b/lib/ICM-20948/src/util/ICM20948_eMD_nucleo_1.0/icm20948_img.dmp3a.h_14290 @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x04, 0xf6, 0xe8, 0xf4, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xa3, 0x88, 0x93, 0xf1, + 0x62, 0x6e, 0x76, 0x7e, 0x88, 0x93, 0xbe, 0xa2, 0x42, 0xa0, 0x4e, 0x56, 0x5e, 0xbe, 0xb9, 0xac, + 0x8d, 0x20, 0xb8, 0xbe, 0xbe, 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, + 0x82, 0x93, 0x01, 0xa9, 0x83, 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, + 0x2c, 0x54, 0x7c, 0xbc, 0xbc, 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, + 0xfd, 0x36, 0x4c, 0xfd, 0x36, 0x6c, 0xfd, 0x36, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, + 0xbd, 0xbd, 0xb1, 0xb6, 0xba, 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, + /* bank # 17 */ + 0x2a, 0xf0, 0x50, 0x78, 0x87, 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, + 0xdf, 0xdf, 0xb0, 0x80, 0xf2, 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, + 0x1e, 0xb2, 0x86, 0xbe, 0xa0, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, + 0x3c, 0xbd, 0xbd, 0xb6, 0x94, 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, + 0xbc, 0xb2, 0x8e, 0x94, 0xb8, 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, + 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, + 0xf5, 0x34, 0x54, 0x74, 0xbc, 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xd4, 0xd8, + 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, + 0x90, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, + 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, 0x11, 0xd4, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, + 0xda, 0xf8, 0xf4, 0x11, 0xd4, 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, + 0xf4, 0x11, 0xd4, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, + 0x92, 0x1a, 0xf8, 0xf9, 0xd1, 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, + 0xda, 0xbc, 0xbd, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, + 0x02, 0xf7, 0x02, 0xf1, 0xbc, 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, + 0xfc, 0x3d, 0x00, 0x50, 0xf8, 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, + /* bank # 18 */ + 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, + 0xf9, 0xd1, 0xbb, 0x81, 0xaa, 0xc1, 0xd9, 0xf4, 0x12, 0x3c, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, + 0xd9, 0xf4, 0x12, 0x3c, 0xd8, 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, + 0xfd, 0x1e, 0xb7, 0x9a, 0x08, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, + 0xa9, 0x80, 0xcd, 0xf2, 0xc4, 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, + 0x91, 0x72, 0x89, 0x91, 0x47, 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x12, 0x6a, 0xd8, 0xf3, 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, + 0xc3, 0xf2, 0xc5, 0xf3, 0xba, 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, + 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, + 0xbe, 0xb5, 0xb9, 0x97, 0xa5, 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, + 0x60, 0xf1, 0xbc, 0xb3, 0x8e, 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, + 0xa7, 0x88, 0x9f, 0xf7, 0x5a, 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, + 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, + 0x9d, 0x60, 0x68, 0x70, 0x78, 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, + 0xf9, 0xba, 0xa0, 0xd0, 0xf3, 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, + 0xd0, 0x64, 0x68, 0x9f, 0x60, 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, + /* bank # 19 */ + 0x85, 0x91, 0xa7, 0xf4, 0x75, 0x9d, 0xf4, 0x75, 0xb5, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0x9d, + 0xf0, 0xa2, 0x87, 0x0d, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, + 0x31, 0x48, 0xb8, 0xb1, 0xb4, 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, + 0x8f, 0x97, 0xf7, 0x02, 0xf9, 0xda, 0xf4, 0x13, 0x74, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, + 0xf9, 0xd9, 0xf4, 0x13, 0x6d, 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, + 0x08, 0xf1, 0xa7, 0x84, 0x94, 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, + 0x81, 0x61, 0xd9, 0xf4, 0x13, 0x8c, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x8c, 0xd8, 0xf1, 0xb8, + 0xb2, 0xa6, 0x82, 0xc0, 0xd8, 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, + 0x04, 0xba, 0x87, 0x91, 0xa7, 0xf4, 0x75, 0xab, 0xb2, 0xf4, 0x75, 0xb5, 0xd8, 0xf1, 0xbe, 0xbe, + 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, + 0x87, 0x91, 0xaf, 0xf4, 0x75, 0x9d, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, + 0x40, 0x69, 0x64, 0x19, 0x31, 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, + 0x8f, 0x91, 0xa7, 0xf4, 0x75, 0xab, 0xf4, 0x75, 0xb5, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, + 0xb4, 0xba, 0x88, 0x9e, 0xa3, 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, + 0x50, 0x78, 0xb2, 0xb9, 0x8a, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, + 0xa1, 0xc2, 0xc5, 0xba, 0xbc, 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, + /* bank # 20 */ + 0xbd, 0xf4, 0x74, 0x91, 0xf3, 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x28, 0xd8, 0x74, + 0xa2, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, + 0x81, 0xc1, 0xc3, 0xf3, 0xa6, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, + 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, + 0xc7, 0x80, 0xad, 0xd0, 0xc0, 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbc, 0xf4, 0x74, 0x91, 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x79, 0xd8, + 0x74, 0xa2, 0xbe, 0xbe, 0xbe, 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, + 0xa9, 0x81, 0xc0, 0xc3, 0xf3, 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, + 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, + 0xd9, 0xf4, 0x14, 0xf7, 0xd8, 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, + 0xb4, 0x84, 0x93, 0x69, 0xd9, 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, + 0xdf, 0xf8, 0xf4, 0x14, 0xc1, 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, + 0xf8, 0xd8, 0xf1, 0x94, 0xfc, 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, + 0x06, 0xfd, 0x1e, 0xa6, 0x81, 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, + 0xf5, 0x83, 0x93, 0x00, 0xa6, 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, + 0x81, 0x9b, 0xdb, 0x19, 0x8b, 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + /* bank # 21 */ + 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, + 0xf4, 0x17, 0x96, 0xd8, 0xf2, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, + 0xde, 0xf8, 0xd8, 0xb2, 0x81, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb4, 0xf1, 0xac, 0x8c, 0x92, 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, + 0xad, 0xc0, 0xbe, 0xbe, 0xba, 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, + 0xde, 0xdf, 0xdf, 0xdf, 0xa5, 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, + 0x9c, 0x11, 0xd9, 0x8c, 0xc5, 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, + 0x9c, 0x45, 0xd9, 0x8f, 0xac, 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, + 0xaf, 0x8f, 0x9f, 0x59, 0xd1, 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, + 0xaf, 0x8f, 0x9f, 0x39, 0xd1, 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, + 0x8f, 0xbe, 0xbe, 0xba, 0xa1, 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, + 0xda, 0xf4, 0x17, 0x69, 0xd8, 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, + 0xf4, 0x17, 0x69, 0xd8, 0xf5, 0x44, 0xd9, 0xf4, 0x17, 0x69, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, + 0x69, 0xd8, 0xf1, 0xb1, 0xb6, 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, + 0x16, 0x1e, 0x8b, 0x9d, 0xab, 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, + 0xaa, 0x2c, 0x54, 0x7c, 0x9b, 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, + /* bank # 22 */ + 0x11, 0x8f, 0x19, 0xf4, 0x16, 0x09, 0xd8, 0x17, 0x69, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, + 0x2d, 0x55, 0x7d, 0xb1, 0x8f, 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, + 0xad, 0x6d, 0xdb, 0x71, 0x79, 0xf4, 0x16, 0x37, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, + 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, 0x16, 0x46, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, + 0xa1, 0xf8, 0xd9, 0xf4, 0x17, 0x69, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, + 0x17, 0x69, 0xd8, 0xf1, 0xba, 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, + 0xc5, 0xb2, 0xb6, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, + 0x86, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xb5, + 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x16, 0xce, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, + 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, + 0x9f, 0x02, 0xf4, 0x16, 0xce, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, + 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, + 0xb1, 0x8c, 0xad, 0xc1, 0xbe, 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, + 0xb2, 0xa0, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, + 0x54, 0x7c, 0xf1, 0xaf, 0x80, 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x08, 0xd8, 0xf2, + /* bank # 23 */ + 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x83, + 0xd8, 0xf1, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, + 0x69, 0xd8, 0xf1, 0x83, 0xb5, 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, + 0xf2, 0xa1, 0xde, 0xf8, 0xf8, 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0x8c, 0xad, 0xc0, 0xaf, 0x9c, 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, + 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, + 0x97, 0x01, 0xd1, 0xb9, 0xa7, 0xc0, 0xda, 0xf4, 0x17, 0x81, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, + 0xd1, 0xda, 0xf3, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, + 0x85, 0x9c, 0x08, 0xbe, 0xbc, 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, + 0xb0, 0xaf, 0x9e, 0x88, 0x62, 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb1, 0x85, 0xba, 0xb5, 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, + 0x81, 0x90, 0x2d, 0x55, 0x7d, 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, + 0xaf, 0x86, 0x9f, 0x69, 0xdb, 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, + 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, + 0xd8, 0xaf, 0x80, 0x90, 0x69, 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, + /* bank # 24 */ + 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, 0x19, 0xc6, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, + 0xb1, 0xad, 0x8a, 0x9e, 0x26, 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x0c, + 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x51, 0xd8, 0xf1, + 0xaf, 0x8a, 0x9a, 0x21, 0x8f, 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x51, 0xd8, 0xf1, 0x91, 0xfc, + 0xc0, 0x04, 0xd9, 0xf4, 0x18, 0x98, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, + 0xc6, 0xf3, 0x91, 0xfc, 0xc0, 0x07, 0xd9, 0xf4, 0x18, 0x98, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, + 0x01, 0xb3, 0xb5, 0x80, 0x97, 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0x98, 0xd8, + 0xf3, 0xb9, 0xa7, 0xde, 0xf8, 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa5, 0x89, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, + 0xc5, 0xc7, 0xf3, 0xa1, 0xde, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, + 0xd1, 0xda, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, + 0x55, 0x7d, 0xf5, 0xb5, 0xa8, 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, + 0x31, 0x39, 0xf4, 0x19, 0xdc, 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, + 0xa0, 0x81, 0x90, 0x2d, 0x55, 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, + 0xdc, 0xd8, 0xf1, 0xba, 0xb0, 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa2, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, + /* bank # 25 */ + 0xac, 0x8c, 0xc2, 0xf3, 0xae, 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x83, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, + 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, + 0xc7, 0xa6, 0x85, 0xc0, 0xc3, 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, + 0x86, 0x96, 0x06, 0xfd, 0x0f, 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, + 0x2e, 0xfd, 0x0f, 0x84, 0x9f, 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, + 0xdb, 0x71, 0x79, 0x8b, 0x9c, 0x61, 0xf4, 0x19, 0x5c, 0xda, 0x19, 0xdc, 0xd8, 0xf1, 0xab, 0x83, + 0x91, 0x28, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, + 0x8b, 0x95, 0x05, 0x2d, 0x55, 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, + 0xa2, 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x0c, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, + 0x8d, 0x9a, 0x01, 0xf5, 0x8f, 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xdc, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, + 0xae, 0x8b, 0xc1, 0xc3, 0xc5, 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa9, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, + 0xc3, 0xc5, 0xc7, 0xf4, 0x19, 0xdc, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, + 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, + 0xdf, 0xba, 0xae, 0xde, 0xbb, 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, + 0xd1, 0xac, 0xc0, 0xd9, 0xae, 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, + /* bank # 26 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbb, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, 0x81, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, + 0x49, 0xda, 0xc3, 0xc5, 0xd9, 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, + 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, + 0xb1, 0x89, 0xc2, 0xb3, 0xaf, 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, + 0xf3, 0xae, 0xdf, 0xf8, 0xf8, 0xf4, 0x1c, 0x38, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, + 0xdf, 0xf8, 0xfd, 0x0f, 0xad, 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, + 0xb7, 0x92, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, 0x20, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x87, 0xd8, 0xf1, 0xd8, 0xf3, 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x36, + 0xd8, 0xf1, 0xaf, 0xde, 0xf9, 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, + 0x78, 0xfd, 0x0f, 0xf1, 0xa2, 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, + 0xfd, 0x0f, 0x0c, 0x30, 0xfd, 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, + 0x54, 0x7c, 0xaa, 0x82, 0x99, 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, + 0x0f, 0xac, 0x83, 0x9f, 0xf0, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, + 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, + 0xc1, 0x82, 0xc1, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, + /* bank # 27 */ + 0x08, 0xd9, 0xc5, 0x8a, 0xc5, 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, + 0xc7, 0xd8, 0xfc, 0xc0, 0x10, 0xd9, 0xf4, 0x1b, 0xf0, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, + 0x2e, 0xfd, 0x0f, 0xa0, 0xde, 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, + 0x8b, 0x90, 0x00, 0xb9, 0xa9, 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x38, 0xd8, 0xf1, 0xba, + 0xb1, 0xb6, 0x89, 0xab, 0xc1, 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, + 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, + 0xc7, 0x84, 0xab, 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, + 0x30, 0xaa, 0x9a, 0x40, 0xd8, 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, + 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, + 0x40, 0x84, 0xab, 0xd0, 0xc4, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, + 0x8f, 0x30, 0xaa, 0x9a, 0x4c, 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, + 0xab, 0xd0, 0xc6, 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, + 0xaa, 0x9a, 0x40, 0x85, 0xab, 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, + 0xa5, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, + 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xe6, + 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, + /* bank # 28 */ + 0xfd, 0x0f, 0x46, 0xfd, 0x0f, 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, + 0x7c, 0xb6, 0x82, 0x92, 0xa0, 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, + 0xda, 0x82, 0xad, 0xc7, 0xd8, 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x10, 0xd8, 0xfc, + 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x0b, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, + 0x89, 0x99, 0xaf, 0x31, 0xd9, 0xf4, 0x1c, 0x8c, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, + 0xc2, 0xd8, 0x85, 0xaf, 0x49, 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, + 0xc6, 0xd8, 0x89, 0xaf, 0x39, 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x8c, 0xd8, 0xf1, 0x89, 0xaa, + 0x7c, 0xfd, 0x02, 0x9a, 0x68, 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, + 0x8f, 0x95, 0x25, 0x89, 0x9f, 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x75, 0xd8, 0xf3, 0x9e, 0xfc, + 0xc1, 0x04, 0xd9, 0xf4, 0x1b, 0x3d, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x58, 0xd8, 0xf1, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, + 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, + 0xde, 0xd8, 0xbc, 0xbc, 0xf1, 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, + 0xa4, 0xde, 0xd8, 0xac, 0x88, 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, + 0x88, 0x95, 0xa4, 0xfc, 0x08, 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, + 0xf6, 0x02, 0xf8, 0xf9, 0xd1, 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, + /* bank # 29 */ + 0x88, 0x92, 0x18, 0xbc, 0xbc, 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, + 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, + 0xd9, 0xf2, 0xac, 0x8c, 0x97, 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, + 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xd6, + 0xd8, 0xf1, 0xbe, 0xbe, 0xac, 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, + 0xbd, 0xbd, 0x95, 0xfc, 0xc0, 0x07, 0xda, 0xf4, 0x1e, 0x71, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, + 0x9c, 0xfc, 0xc1, 0x00, 0xf4, 0x1e, 0x96, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, + 0x1d, 0xb3, 0xd8, 0xf1, 0x82, 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, + 0xf1, 0xbc, 0xbc, 0xbc, 0x80, 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x91, 0xda, 0xbc, 0x1e, + 0x6d, 0xd8, 0xf5, 0x86, 0x98, 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, + 0xf5, 0x5c, 0xd9, 0xf1, 0x82, 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, + 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, + 0x95, 0xf5, 0x1c, 0xd9, 0xf4, 0x1e, 0x6d, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, + 0xac, 0x8c, 0x9c, 0x06, 0xd2, 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, + 0x28, 0xd3, 0x87, 0xd4, 0xa7, 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, + 0xac, 0x83, 0x90, 0x45, 0xd9, 0xf4, 0x1e, 0x96, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, + /* bank # 30 */ + 0x85, 0x66, 0xfd, 0x1d, 0x88, 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, + 0x81, 0x9c, 0xab, 0xd6, 0xfd, 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, + 0x8b, 0x98, 0xf5, 0x08, 0xd9, 0xf4, 0x1e, 0x6d, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, + 0xc1, 0x00, 0xda, 0xf4, 0x1e, 0x45, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, + 0xf8, 0xd8, 0xf4, 0x1e, 0x71, 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x06, 0x54, 0xfd, 0x06, + 0x74, 0xfd, 0x06, 0xa9, 0x94, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, + 0x59, 0x84, 0xab, 0xc3, 0xc5, 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, + 0xdf, 0xd8, 0xf1, 0xa0, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, + 0xdf, 0xa2, 0x95, 0xfc, 0xc0, 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, + 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, + 0x01, 0xf3, 0xaa, 0xde, 0xf8, 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, + 0xd8, 0xac, 0x8a, 0x9a, 0x41, 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, + 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xf4, 0x1e, 0xd6, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xa5, 0x85, 0x9c, 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, + 0xf9, 0xd9, 0xf4, 0x20, 0x0d, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, + 0x20, 0x0d, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, + /* bank # 31 */ + 0x84, 0xbd, 0xbd, 0xbd, 0xb7, 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, + 0x9f, 0x46, 0x8f, 0xa2, 0x0e, 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, + 0xfb, 0x86, 0x95, 0xaf, 0x29, 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x41, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x41, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, + 0xf8, 0xd8, 0xf1, 0x85, 0x94, 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, + 0x85, 0x96, 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, + 0xa8, 0xdf, 0xa1, 0xde, 0x85, 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, + 0x97, 0xfc, 0xc0, 0x04, 0xdb, 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, + 0xd9, 0xf4, 0x1f, 0xa9, 0xd8, 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xd2, 0xd8, 0xf1, 0x93, + 0xfc, 0xc0, 0x09, 0xd9, 0xa4, 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, + 0xa1, 0xc1, 0xa7, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xeb, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, + 0x31, 0xdb, 0x9f, 0x71, 0x92, 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, + 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, + 0x1f, 0xeb, 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, + 0xa1, 0xc2, 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, + 0x04, 0xd9, 0xa7, 0xfa, 0xa3, 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, + /* bank # 32 */ + 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, + 0xa7, 0xde, 0xf7, 0x84, 0x9f, 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x3d, + 0xd8, 0xf0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x3d, 0xd8, 0xf2, 0xbb, 0xa0, + 0xf9, 0xda, 0xf4, 0x20, 0x3d, 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xd1, 0xd8, 0xf0, 0xb1, + 0xb5, 0xba, 0x8a, 0x9a, 0xa7, 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, + 0xb2, 0xa7, 0x87, 0x90, 0x21, 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, + 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, + 0xa7, 0x82, 0x95, 0x65, 0xd1, 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, + 0xd1, 0xf4, 0x20, 0x8d, 0xd8, 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, + 0xb2, 0xb6, 0x81, 0x96, 0xa1, 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, + 0x6d, 0xd8, 0xba, 0x8a, 0xaa, 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, + 0x6d, 0xd8, 0xba, 0x88, 0xa8, 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, + 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, + 0x93, 0xf6, 0x0a, 0xf2, 0xb4, 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, + 0xbe, 0xbb, 0xae, 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, + /* bank # 33 */ + 0x85, 0x9e, 0xa5, 0x08, 0xd8, 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, + 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, + 0xb8, 0xb4, 0xf3, 0x98, 0xfc, 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x7b, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, + 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, + 0x9a, 0xa7, 0x29, 0xd9, 0xa8, 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, + 0xa7, 0x51, 0xd9, 0xa8, 0xd0, 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, + 0xa7, 0x79, 0xd9, 0xa8, 0xd0, 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, + 0x9b, 0xa7, 0x51, 0xd9, 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, + 0x52, 0xf9, 0xd9, 0xf4, 0x21, 0xab, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, + 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, + 0x88, 0x9a, 0xa7, 0x01, 0xd9, 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, + 0x42, 0xf9, 0xd9, 0xf4, 0x21, 0xf2, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, + 0xde, 0xa4, 0x84, 0x9c, 0x3c, 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, + 0x84, 0x9c, 0x34, 0xd8, 0xf2, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, + 0x9e, 0x34, 0xd8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, + 0x9e, 0x24, 0xd8, 0xf1, 0xa7, 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, + /* bank # 34 */ + 0xf7, 0x85, 0x02, 0xf8, 0xf9, 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x23, 0xe7, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, + 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, + 0xdc, 0xd8, 0x85, 0x95, 0xa5, 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, + 0x85, 0x00, 0xd9, 0x80, 0xf0, 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, + 0x85, 0x00, 0xd9, 0xb1, 0x89, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, + 0xd9, 0x81, 0xf0, 0xdd, 0xf2, 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, + 0x86, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, + 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0x85, 0x00, 0xb1, 0xd9, 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, + 0x00, 0xd9, 0xb1, 0x8e, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, + 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, + 0xd8, 0x85, 0x00, 0xd8, 0xf2, 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, + 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, + 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x23, 0x69, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, + 0xd9, 0xbe, 0xf2, 0xba, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, + /* bank # 35 */ + 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, + 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, + 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, + 0xb8, 0xa5, 0x00, 0xd9, 0xb3, 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, + 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, + 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, + 0xd0, 0xc0, 0xd8, 0x87, 0xf3, 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x23, 0x72, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, + 0xdf, 0xf3, 0x30, 0xfd, 0x08, 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, + 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, + 0xb5, 0x9f, 0x30, 0xa6, 0x39, 0xd9, 0xf4, 0x23, 0xe1, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, + 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, 0x23, 0xd4, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, + 0xd9, 0xf4, 0x23, 0xe7, 0xd8, 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, + 0xda, 0xf0, 0xe2, 0xf1, 0xb9, 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, + 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, + /* bank # 36 */ + 0xdf, 0xf7, 0x62, 0xf3, 0xf8, 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, + 0x9d, 0x66, 0x9e, 0x76, 0x9f, 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, + 0xf9, 0xda, 0xff, 0xd8, 0xb3, 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, + 0xf4, 0x25, 0xaf, 0xd8, 0xf1, 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, + 0xc1, 0xf7, 0x88, 0xb4, 0x9d, 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, + 0x24, 0x84, 0xd8, 0xf1, 0xb8, 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, + 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, + 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, + 0xbe, 0xf4, 0x24, 0xeb, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, + 0xf5, 0x87, 0x95, 0xa7, 0x3a, 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, + 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, + 0xfc, 0xc1, 0x00, 0xd9, 0xaf, 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, + 0xa7, 0xde, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, + 0xd0, 0xde, 0x40, 0x48, 0x50, 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, + 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, + 0xc1, 0xbc, 0x84, 0xb8, 0xbe, 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, + /* bank # 37 */ + 0xbd, 0xda, 0xf4, 0x25, 0x38, 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, + 0xbc, 0x8e, 0xbe, 0xae, 0xd0, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, + 0x40, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, + 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, 0xf4, 0x25, 0xa2, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, + 0xfc, 0xc0, 0x04, 0xf5, 0x89, 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, + 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, + 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, + 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, + 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, + 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, + 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, + 0xf1, 0xb2, 0x80, 0xba, 0xa7, 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x6a, 0x8f, 0xb6, 0x9c, 0xf4, + 0x75, 0x76, 0xaf, 0xf4, 0x75, 0x7c, 0x8b, 0xf4, 0x75, 0x6a, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x76, + 0xae, 0xf4, 0x75, 0x7c, 0xb3, 0x81, 0xf4, 0x75, 0x6a, 0x85, 0x94, 0xf4, 0x75, 0x76, 0xbb, 0xa5, + 0xf4, 0x75, 0x7c, 0x80, 0xba, 0xf4, 0x75, 0x6a, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x76, 0xbb, 0xae, + 0xf4, 0x75, 0x7c, 0xb3, 0x83, 0xa3, 0xf4, 0x75, 0x88, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, + /* bank # 38 */ + 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, + 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, + 0x86, 0xaf, 0x42, 0x4e, 0x76, 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, + 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, + 0xd0, 0x3e, 0x80, 0x93, 0xaf, 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, + 0x83, 0x9b, 0xa7, 0x69, 0xdb, 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x62, 0xd8, 0xf1, 0xad, + 0xde, 0xdf, 0xd8, 0xf0, 0xbc, 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, + 0x2c, 0x50, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, + 0x7c, 0x9b, 0x71, 0x97, 0xa5, 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, + 0xf5, 0xb0, 0x8c, 0xb7, 0x93, 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, + 0xba, 0x86, 0xa7, 0xc2, 0xf4, 0x75, 0x90, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, + 0x76, 0xf1, 0xa4, 0xf4, 0x75, 0x7c, 0x83, 0xa3, 0xf4, 0x75, 0x88, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, + 0x75, 0x90, 0x95, 0xf0, 0x71, 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x76, 0xa6, 0xf4, 0x75, 0x7c, + 0x85, 0xa5, 0xf4, 0x75, 0x88, 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x90, 0x9f, 0xf0, 0x71, 0x71, + 0x60, 0x88, 0x92, 0xf4, 0x75, 0x76, 0xa8, 0xf4, 0x75, 0x7c, 0x8f, 0xaf, 0xf4, 0x75, 0x88, 0xf5, + 0xb2, 0x84, 0x94, 0xb9, 0xaf, 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, + /* bank # 39 */ + 0x9f, 0xa5, 0x30, 0x85, 0x18, 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, + 0xaf, 0xc3, 0xc5, 0xc7, 0xba, 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, + 0xa7, 0x87, 0xb6, 0x97, 0x2c, 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, + 0x97, 0x30, 0x9c, 0x1c, 0x97, 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, + 0x9c, 0x59, 0xdb, 0x51, 0xaa, 0xde, 0xf4, 0x27, 0x5f, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, + 0xfd, 0x02, 0xb2, 0x8b, 0x02, 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, + 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xdf, 0xd8, 0xf1, + 0xb2, 0xbc, 0xbc, 0x84, 0xb8, 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, + 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, + 0x7c, 0x99, 0x71, 0x8a, 0x59, 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, + 0xfd, 0x01, 0x8e, 0xa9, 0xc2, 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, + 0x97, 0xaf, 0x09, 0x8f, 0xb5, 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, + 0xba, 0xa7, 0xc1, 0xc3, 0xc5, 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, + 0x28, 0x6c, 0xd8, 0xf1, 0xb2, 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0x96, 0x9a, 0xf4, + 0x75, 0x76, 0x8a, 0xaa, 0xf4, 0x75, 0x88, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0x96, + 0x9c, 0xf4, 0x75, 0x76, 0x8c, 0xac, 0xf4, 0x75, 0x88, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, + /* bank # 40 */ + 0x75, 0x96, 0x9e, 0xf4, 0x75, 0x76, 0x8e, 0xae, 0xf4, 0x75, 0x88, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, + 0xc7, 0x87, 0xc3, 0x8b, 0xab, 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, + 0xc7, 0xb8, 0xae, 0xde, 0x8a, 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, + 0xfd, 0x01, 0xb0, 0xf0, 0x8d, 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, + 0x8d, 0x39, 0x9e, 0x7c, 0x9c, 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, + 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, + 0x50, 0xf1, 0x88, 0x98, 0xaf, 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, + 0xb4, 0xbc, 0xbc, 0xbc, 0x84, 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, + 0xaf, 0x49, 0xda, 0xf4, 0x28, 0x9c, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, + 0x90, 0xfc, 0xc0, 0x00, 0xd9, 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xac, 0xd8, 0xf5, 0x91, 0x72, + 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xa0, 0xda, 0xf8, 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, + 0xfc, 0xc1, 0x04, 0xd9, 0xa1, 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, + 0xde, 0xdf, 0xa1, 0xdf, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, + 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, + 0x21, 0xd9, 0xf4, 0x30, 0x26, 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, + /* bank # 41 */ + 0xdf, 0xdf, 0xab, 0xde, 0xac, 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, + 0xbe, 0xbe, 0xbe, 0x83, 0xa9, 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, + 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x79, 0xd8, 0xf1, 0xaa, + 0xde, 0x99, 0xfc, 0xc1, 0x00, 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, + 0xd8, 0xf5, 0xa2, 0x89, 0x92, 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, + 0x82, 0xdb, 0x31, 0xdf, 0xaa, 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, + 0xf2, 0x89, 0x99, 0xa9, 0x71, 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0xa8, 0xde, 0x98, 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, + 0xbe, 0x87, 0x94, 0xaf, 0x19, 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x6f, 0xd8, 0xf1, 0x82, 0x9f, + 0xaf, 0xdf, 0x28, 0xfd, 0x03, 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, + 0xde, 0xd9, 0xf8, 0xda, 0xf4, 0x2a, 0xe0, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, + 0xc7, 0x83, 0xa7, 0xd0, 0xc2, 0xf4, 0x2a, 0x11, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, + 0x2a, 0x11, 0xd8, 0xf5, 0xb3, 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, + 0xf4, 0x2a, 0x11, 0xd8, 0xf5, 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x11, + 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, + 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, + /* bank # 42 */ + 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, + 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, + 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, + 0xc7, 0xa0, 0xdf, 0xd0, 0xde, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, + 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, + 0xd8, 0x8f, 0x93, 0xaf, 0x21, 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, + 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, + 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, + 0x2a, 0xaf, 0xd8, 0xf3, 0xbc, 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, + 0xc5, 0xb1, 0xbc, 0x80, 0x93, 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, + 0x9f, 0xfc, 0xc1, 0x04, 0xf2, 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, + 0xf1, 0xa1, 0xd0, 0xde, 0x83, 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xc9, 0xd8, 0xf2, + 0x8f, 0x9f, 0x71, 0xd9, 0xf1, 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, + 0xd9, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x4f, 0xd8, 0xf4, 0x2c, 0xb0, + 0xd8, 0xf1, 0x82, 0x9d, 0xaf, 0x31, 0xda, 0xf4, 0x2b, 0x11, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, + 0xb6, 0x9d, 0xfc, 0xc2, 0x04, 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, + /* bank # 43 */ + 0xaf, 0x19, 0xb1, 0x88, 0xa4, 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, + 0x4f, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0xba, 0xad, 0xf8, + 0xf9, 0xd1, 0xd9, 0x83, 0xb9, 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, + 0xd0, 0xc6, 0xf4, 0x2b, 0x4f, 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, + 0xbb, 0xaf, 0x19, 0xb1, 0xa4, 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, + 0xf1, 0xb1, 0x85, 0xba, 0xbe, 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, + 0xa7, 0xdf, 0xdf, 0x8f, 0x92, 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x91, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, + 0x2b, 0x78, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x85, 0xd8, + 0xf1, 0xfa, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, + 0xc0, 0xd8, 0xf1, 0x93, 0x21, 0xd9, 0xf4, 0x2b, 0xa5, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, + 0xfa, 0xd8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, + 0x59, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xc0, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, + 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, + 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, + 0xc3, 0x04, 0xfc, 0xc0, 0x00, 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, + 0x94, 0xa7, 0x71, 0xd9, 0xf4, 0x2c, 0x09, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x09, 0xd8, + /* bank # 44 */ + 0xf1, 0x94, 0x09, 0xdb, 0x39, 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, + 0xbc, 0xbc, 0xbc, 0x83, 0xb9, 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, + 0x04, 0xd0, 0xd9, 0xc7, 0xda, 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, + 0xfc, 0xc1, 0x00, 0xd9, 0xf4, 0x2c, 0xb0, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, + 0x50, 0x78, 0xf1, 0xba, 0xaa, 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, + 0x8e, 0xbb, 0xab, 0xc7, 0xd8, 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, + 0x90, 0x79, 0xdb, 0xd1, 0xb9, 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xb0, 0xd8, + 0xf1, 0xb0, 0xbc, 0x81, 0xb9, 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, + 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, + 0x2d, 0x8d, 0x9f, 0x31, 0xd9, 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, + 0xf5, 0x06, 0xf1, 0xdb, 0xfc, 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf5, 0xb3, 0x89, 0xb7, 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, + 0x03, 0xd9, 0x8f, 0xa9, 0xd0, 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, + 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, + 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, + 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, + /* bank # 45 */ + 0xa9, 0xc0, 0xd8, 0xa3, 0xde, 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, + 0x2d, 0x83, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, + 0xf4, 0x2d, 0x7a, 0xd8, 0xf1, 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, + 0x8c, 0x95, 0x69, 0xd9, 0xdf, 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, + 0xf4, 0x2d, 0x57, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, + 0xd0, 0x80, 0x9c, 0x48, 0xd8, 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, + 0xb5, 0xd9, 0xa0, 0xd0, 0xde, 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, + 0xfc, 0xc0, 0x00, 0xa0, 0xd0, 0xde, 0xd8, 0xf4, 0x2d, 0x83, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, + 0xde, 0xda, 0xf8, 0xd8, 0xf1, 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, + 0xfc, 0xc2, 0x00, 0xd9, 0xb2, 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xb2, + 0xd8, 0xf1, 0x84, 0xb4, 0x9f, 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xb2, 0xd8, 0xf1, + 0xae, 0xde, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, + 0xb5, 0x9d, 0xa1, 0x02, 0xb7, 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, + 0x12, 0x26, 0x5e, 0x6e, 0xb3, 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, + 0x54, 0x7c, 0xaf, 0xde, 0xf8, 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, + 0x8a, 0xaa, 0xc4, 0xd8, 0x83, 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x40, 0xd8, 0xf1, 0xa2, 0xd0, + /* bank # 46 */ + 0xde, 0xb6, 0x9e, 0xfc, 0xc0, 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, + 0xde, 0xfa, 0xb7, 0xbb, 0xf4, 0x2e, 0x40, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, + 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, + 0x8d, 0x94, 0x1d, 0xf1, 0xe2, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, + 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x19, 0xd9, 0xf4, 0x2e, 0x84, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, + 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x72, 0xd8, 0xf1, 0x8e, 0x91, 0x41, + 0xd9, 0xf4, 0x2e, 0x72, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, + 0x2e, 0xff, 0xd8, 0xf1, 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, + 0xc6, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, + 0xaf, 0x59, 0xb3, 0xb7, 0xd1, 0xd9, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, + 0xa3, 0xf8, 0xad, 0xde, 0xd8, 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xda, + 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, + 0x60, 0xad, 0xf8, 0xaf, 0xde, 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, + 0x9d, 0xaf, 0x21, 0xa3, 0xde, 0xf8, 0xd8, 0xf4, 0x2e, 0xff, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, + 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, + 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, + /* bank # 47 */ + 0xf5, 0x83, 0x9a, 0xaf, 0x1a, 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, + 0xbc, 0xbc, 0xb1, 0x8b, 0x34, 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, + 0xd9, 0xf4, 0x2f, 0x59, 0xd8, 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, + 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, + 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, + 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf4, 0x2f, 0x97, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, + 0xf5, 0x8e, 0xae, 0x32, 0xf1, 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, + 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0x97, 0xd8, 0xf1, 0xa6, 0xfa, + 0x86, 0x96, 0xae, 0x39, 0xd9, 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, + 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, + 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, + 0xde, 0x85, 0xa5, 0xd0, 0xc6, 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xd7, 0xd8, 0xf1, + 0x89, 0x93, 0xa3, 0x60, 0xf3, 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, + 0xbe, 0xbe, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, + 0x0d, 0xf5, 0x99, 0xaf, 0x1a, 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, + 0xdf, 0xf9, 0x89, 0x9f, 0x4d, 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, + /* bank # 48 */ + 0xc0, 0x03, 0xd9, 0xf5, 0xa8, 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, + 0x38, 0x86, 0x9f, 0xaf, 0xde, 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, + 0xbc, 0xb1, 0x82, 0xc3, 0xbc, 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, + 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, + 0xf1, 0xb9, 0xac, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, + 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, + 0x40, 0x99, 0x6c, 0x97, 0x48, 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, + 0x83, 0x65, 0xd9, 0xf4, 0x30, 0x89, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, + 0xc3, 0xc1, 0xda, 0xc1, 0xc3, 0xd8, 0xf4, 0x75, 0x4a, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, + 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, + 0xd9, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, + 0x1a, 0xf0, 0x96, 0x40, 0x9d, 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, + 0x0a, 0x8d, 0x96, 0x05, 0xd9, 0xf4, 0x30, 0xf0, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, + 0x49, 0xf9, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xf0, 0xd8, + 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x01, + 0xd8, 0xf1, 0xb3, 0x85, 0xbb, 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, + /* bank # 49 */ + 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, + 0xde, 0xd8, 0xf2, 0xbb, 0xaf, 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, + 0xac, 0xd0, 0xc5, 0xf3, 0xa7, 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, + 0xc1, 0x00, 0xb8, 0xbe, 0xa7, 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, + 0x98, 0x19, 0xa9, 0x80, 0xd9, 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, + 0xf8, 0xf9, 0xd1, 0xda, 0xf9, 0xdf, 0xf8, 0xf4, 0x75, 0x32, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, + 0xf5, 0x75, 0xda, 0xff, 0xd8, 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, + 0xc2, 0xf1, 0x97, 0x86, 0x49, 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, + 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, + 0x70, 0x70, 0xf1, 0xd8, 0xb7, 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, + 0x2e, 0xd8, 0x89, 0x99, 0xaf, 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, + 0xdf, 0xd8, 0xaf, 0x82, 0xf3, 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, + 0x8f, 0x99, 0xaf, 0x51, 0xdb, 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, + 0x71, 0xd9, 0xf1, 0xdf, 0xf9, 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, + 0xbb, 0x82, 0xac, 0xf3, 0xc0, 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, + 0xac, 0xde, 0xff, 0xd8, 0xa2, 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, + /* bank # 50 */ + 0x81, 0xc5, 0xb0, 0xbc, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x28, + 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x49, 0xda, 0xf4, 0x32, 0x28, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, + 0xa7, 0xd0, 0xd9, 0x88, 0x97, 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, + 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, + 0xbd, 0x9f, 0xba, 0xa7, 0x61, 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, + 0xb1, 0x84, 0xb6, 0x96, 0xba, 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, + 0xdb, 0xb3, 0x8d, 0xb6, 0x97, 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, + 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, + 0xb7, 0xbb, 0x97, 0x8c, 0xaf, 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0x9b, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, + 0x34, 0xaa, 0xd0, 0x8a, 0x50, 0xf4, 0x75, 0x32, 0xf4, 0x32, 0xbb, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, + 0xb5, 0x9c, 0xfc, 0xc2, 0x07, 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, + 0x91, 0xa1, 0x6c, 0xaa, 0xd0, 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x32, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, + 0x0a, 0xd9, 0xf4, 0x32, 0xfc, 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, + 0xa6, 0xd0, 0x38, 0xfd, 0x31, 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, + 0x0f, 0x8d, 0x9f, 0x65, 0xd9, 0xf4, 0x32, 0xfc, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, + 0x82, 0x9f, 0x25, 0xd9, 0xf1, 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, + /* bank # 51 */ + 0xfc, 0xc1, 0x03, 0xd9, 0xbc, 0xbd, 0xbe, 0xf4, 0x33, 0x30, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, + 0xde, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x30, 0xd8, 0xf1, + 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, + 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, + 0xf1, 0xb0, 0x83, 0xb4, 0x93, 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, + 0x78, 0x8e, 0xbe, 0xb9, 0xaa, 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, + 0x31, 0xda, 0xf4, 0x33, 0xd4, 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, + 0x0c, 0x30, 0xba, 0x8d, 0x9d, 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, + 0x84, 0xb5, 0x94, 0xb9, 0xa4, 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, + 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, + 0x81, 0xb9, 0xa1, 0x34, 0xda, 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, + 0x4e, 0x81, 0xb9, 0xa1, 0x34, 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, + 0xd0, 0xdf, 0xf1, 0xff, 0xd8, 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, + 0x09, 0xaa, 0xd0, 0x8a, 0x9d, 0xd9, 0x74, 0xf4, 0x33, 0xef, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, + 0xf3, 0xb9, 0xac, 0xd0, 0xf8, 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, + /* bank # 52 */ + 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, + 0x61, 0xd9, 0xf2, 0xa1, 0xd0, 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, + 0x8f, 0xb7, 0x91, 0x15, 0xda, 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, + 0xb9, 0xac, 0xde, 0xad, 0xde, 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, + 0x91, 0xaf, 0x31, 0xda, 0xf1, 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, + 0x91, 0xaf, 0x31, 0xd1, 0xd9, 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, + 0x8c, 0xb7, 0x9c, 0xbb, 0xac, 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, + 0xca, 0xf2, 0x91, 0x35, 0xf1, 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, + 0xa6, 0x8f, 0x96, 0x01, 0x8a, 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, + 0xff, 0xd8, 0xf0, 0xb9, 0xb1, 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, + 0x79, 0xe0, 0xd8, 0xf1, 0xba, 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, + 0x82, 0x90, 0x25, 0xf3, 0xad, 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, + 0x82, 0x38, 0xf1, 0xaa, 0x2d, 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, + 0x8f, 0x9f, 0x04, 0x28, 0x51, 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, + 0x9a, 0x2c, 0x50, 0x50, 0x78, 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, + 0xd8, 0xf1, 0xb8, 0xae, 0x82, 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, + /* bank # 53 */ + 0x81, 0xc1, 0xf3, 0xad, 0xfb, 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, + 0xd1, 0xda, 0xaa, 0x82, 0x9d, 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, + 0x54, 0x78, 0xfd, 0x7f, 0xf1, 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, + 0x91, 0xe0, 0xd8, 0xf1, 0xb1, 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, + 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, + 0x85, 0xa5, 0xd0, 0xda, 0xc6, 0xf4, 0x35, 0x67, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, + 0xad, 0xd0, 0x8d, 0x9e, 0x7f, 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, + 0x93, 0xf0, 0x71, 0x71, 0x60, 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, + 0xb2, 0x87, 0xb6, 0x97, 0x2c, 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, + 0xf1, 0xb2, 0x81, 0x97, 0x66, 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, + 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, + 0x34, 0x49, 0x2d, 0x51, 0xe0, 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, + 0x28, 0x50, 0x78, 0xfd, 0x7f, 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, + 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, + 0xf4, 0x78, 0x4e, 0x8d, 0xad, 0xf4, 0x78, 0x4e, 0x8e, 0xae, 0xf4, 0x78, 0x4e, 0xbc, 0xb0, 0x80, + 0xba, 0xaf, 0xf1, 0xde, 0xdf, 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, + /* bank # 54 */ + 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, + 0xbd, 0xb5, 0x90, 0xbb, 0xaf, 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, + 0x16, 0xf0, 0x38, 0x92, 0x40, 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, + 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x36, 0x3f, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x11, 0xd8, + 0xf0, 0xb7, 0x8c, 0x9c, 0xba, 0xf4, 0x78, 0x1d, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, + 0x1d, 0xf1, 0x1c, 0xb3, 0x8e, 0x9e, 0xba, 0xf4, 0x78, 0x1d, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, + 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, + 0xd0, 0x2a, 0xd2, 0xf0, 0x00, 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, + 0xa9, 0xf8, 0xd8, 0x97, 0xaf, 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, + 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xb8, 0xd8, 0xf2, 0xb5, 0x97, 0xde, + 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, + 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, + 0x8f, 0x9e, 0x05, 0xda, 0xf4, 0x36, 0xe3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, + 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, + 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, + 0xf5, 0x00, 0xb1, 0x88, 0x04, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, + /* bank # 55 */ + 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, + 0xb1, 0x88, 0xd0, 0xf5, 0x44, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, + 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x3a, 0xd8, + 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, + 0xaf, 0x68, 0xd9, 0xaa, 0xfa, 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, + 0xfd, 0x40, 0x8f, 0xd0, 0xf5, 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, + 0xd0, 0xd9, 0xdf, 0xda, 0xfa, 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, + 0x9a, 0xd0, 0xf5, 0x04, 0xa9, 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, + 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, + 0x10, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, + 0xbd, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x37, 0xb2, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, + 0x37, 0xc8, 0xd8, 0xf1, 0xb1, 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xc8, 0xd8, 0xf1, 0xb5, + 0x9b, 0xb3, 0x8f, 0x41, 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, + 0xda, 0xf4, 0x37, 0xe7, 0xd8, 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xe7, 0xd8, 0xf1, 0xb5, 0x9b, + 0xb3, 0x8f, 0x49, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, + /* bank # 56 */ + 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, + 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, + 0x11, 0x3d, 0xf3, 0x15, 0x3d, 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, + 0xf1, 0xd4, 0xfd, 0x70, 0xd5, 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, + 0x10, 0x18, 0xf5, 0x00, 0xb5, 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, + 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, + 0xc9, 0xe0 diff --git a/lib/ICM-20948/src/util/ICM_20948_C.c b/lib/ICM-20948/src/util/ICM_20948_C.c new file mode 100644 index 0000000..356e44f --- /dev/null +++ b/lib/ICM-20948/src/util/ICM_20948_C.c @@ -0,0 +1,2543 @@ +#include "ICM_20948_C.h" +#include "ICM_20948_REGISTERS.h" +#include "AK09916_REGISTERS.h" + +/* + * Icm20948 device require a DMP image to be loaded on init + * Provide such images by mean of a byte array +*/ +#if defined(ICM_20948_USE_DMP) // Only include the 14301 Bytes of DMP if ICM_20948_USE_DMP is defined + +#if defined(ARDUINO_ARCH_MBED) // ARDUINO_ARCH_MBED (APOLLO3 v2) does not support or require pgmspace.h / PROGMEM +const uint8_t dmp3_image[] = { +#elif (defined(__AVR__) || defined(__arm__) || defined(__ARDUINO_ARC__)) && !defined(__linux__) // Store the DMP firmware in PROGMEM on older AVR (ATmega) platforms +#define ICM_20948_USE_PROGMEM_FOR_DMP +#include +const uint8_t dmp3_image[] PROGMEM = { +#else +const uint8_t dmp3_image[] = { +#endif + +#include "icm20948_img.dmp3a.h" +}; +#endif + +// ICM-20948 data is big-endian. We need to make it little-endian when writing into icm_20948_DMP_data_t +const int DMP_Quat9_Byte_Ordering[icm_20948_DMP_Quat9_Bytes] = + { + 3, 2, 1, 0, 7, 6, 5, 4, 11, 10, 9, 8, 13, 12 // Also used for Geomag +}; +const int DMP_Quat6_Byte_Ordering[icm_20948_DMP_Quat6_Bytes] = + { + 3, 2, 1, 0, 7, 6, 5, 4, 11, 10, 9, 8 // Also used for Gyro_Calibr, Compass_Calibr +}; +const int DMP_PQuat6_Byte_Ordering[icm_20948_DMP_PQuat6_Bytes] = + { + 1, 0, 3, 2, 5, 4 // Also used for Raw_Accel, Compass +}; +const int DMP_Raw_Gyro_Byte_Ordering[icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes] = + { + 1, 0, 3, 2, 5, 4, 7, 6, 9, 8, 11, 10}; +const int DMP_Activity_Recognition_Byte_Ordering[icm_20948_DMP_Activity_Recognition_Bytes] = + { + 0, 1, 5, 4, 3, 2}; +const int DMP_Secondary_On_Off_Byte_Ordering[icm_20948_DMP_Secondary_On_Off_Bytes] = + { + 1, 0}; + +const uint16_t inv_androidSensor_to_control_bits[ANDROID_SENSOR_NUM_MAX] = + { + // Data output control 1 register bit definition + // 16-bit accel 0x8000 + // 16-bit gyro 0x4000 + // 16-bit compass 0x2000 + // 16-bit ALS 0x1000 + // 32-bit 6-axis quaternion 0x0800 + // 32-bit 9-axis quaternion + heading accuracy 0x0400 + // 16-bit pedometer quaternion 0x0200 + // 32-bit Geomag rv + heading accuracy 0x0100 + // 16-bit Pressure 0x0080 + // 32-bit calibrated gyro 0x0040 + // 32-bit calibrated compass 0x0020 + // Pedometer Step Detector 0x0010 + // Header 2 0x0008 + // Pedometer Step Indicator Bit 2 0x0004 + // Pedometer Step Indicator Bit 1 0x0002 + // Pedometer Step Indicator Bit 0 0x0001 + // Unsupported Sensors are 0xFFFF + + 0xFFFF, // 0 Meta Data + 0x8008, // 1 Accelerometer + 0x0028, // 2 Magnetic Field + 0x0408, // 3 Orientation + 0x4048, // 4 Gyroscope + 0x1008, // 5 Light + 0x0088, // 6 Pressure + 0xFFFF, // 7 Temperature + 0xFFFF, // 8 Proximity <----------- fixme + 0x0808, // 9 Gravity + 0x8808, // 10 Linear Acceleration + 0x0408, // 11 Rotation Vector + 0xFFFF, // 12 Humidity + 0xFFFF, // 13 Ambient Temperature + 0x2008, // 14 Magnetic Field Uncalibrated + 0x0808, // 15 Game Rotation Vector + 0x4008, // 16 Gyroscope Uncalibrated + 0x0000, // 17 Significant Motion + 0x0018, // 18 Step Detector + 0x0010, // 19 Step Counter <----------- fixme + 0x0108, // 20 Geomagnetic Rotation Vector + 0xFFFF, // 21 ANDROID_SENSOR_HEART_RATE, + 0xFFFF, // 22 ANDROID_SENSOR_PROXIMITY, + + 0x8008, // 23 ANDROID_SENSOR_WAKEUP_ACCELEROMETER, + 0x0028, // 24 ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD, + 0x0408, // 25 ANDROID_SENSOR_WAKEUP_ORIENTATION, + 0x4048, // 26 ANDROID_SENSOR_WAKEUP_GYROSCOPE, + 0x1008, // 27 ANDROID_SENSOR_WAKEUP_LIGHT, + 0x0088, // 28 ANDROID_SENSOR_WAKEUP_PRESSURE, + 0x0808, // 29 ANDROID_SENSOR_WAKEUP_GRAVITY, + 0x8808, // 30 ANDROID_SENSOR_WAKEUP_LINEAR_ACCELERATION, + 0x0408, // 31 ANDROID_SENSOR_WAKEUP_ROTATION_VECTOR, + 0xFFFF, // 32 ANDROID_SENSOR_WAKEUP_RELATIVE_HUMIDITY, + 0xFFFF, // 33 ANDROID_SENSOR_WAKEUP_AMBIENT_TEMPERATURE, + 0x2008, // 34 ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD_UNCALIBRATED, + 0x0808, // 35 ANDROID_SENSOR_WAKEUP_GAME_ROTATION_VECTOR, + 0x4008, // 36 ANDROID_SENSOR_WAKEUP_GYROSCOPE_UNCALIBRATED, + 0x0018, // 37 ANDROID_SENSOR_WAKEUP_STEP_DETECTOR, + 0x0010, // 38 ANDROID_SENSOR_WAKEUP_STEP_COUNTER, + 0x0108, // 39 ANDROID_SENSOR_WAKEUP_GEOMAGNETIC_ROTATION_VECTOR + 0xFFFF, // 40 ANDROID_SENSOR_WAKEUP_HEART_RATE, + 0x0000, // 41 ANDROID_SENSOR_WAKEUP_TILT_DETECTOR, + 0x8008, // 42 Raw Acc + 0x4048, // 43 Raw Gyr +}; + +const ICM_20948_Serif_t NullSerif = { + NULL, // write + NULL, // read + NULL, // user +}; + +// Private function prototypes + +// Function definitions +ICM_20948_Status_e ICM_20948_init_struct(ICM_20948_Device_t *pdev) +{ + // Initialize all elements by 0 except for _last_bank + // Initialize _last_bank to 4 (invalid bank number) + // so ICM_20948_set_bank function does not skip issuing bank change operation + static const ICM_20948_Device_t init_device = { ._last_bank = 4 }; + *pdev = init_device; + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_link_serif(ICM_20948_Device_t *pdev, const ICM_20948_Serif_t *s) +{ + if (s == NULL) + { + return ICM_20948_Stat_ParamErr; + } + if (pdev == NULL) + { + return ICM_20948_Stat_ParamErr; + } + pdev->_serif = s; + return ICM_20948_Stat_Ok; +} + +ICM_20948_Status_e ICM_20948_execute_w(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len) +{ + if (pdev->_serif->write == NULL) + { + return ICM_20948_Stat_NotImpl; + } + return (*pdev->_serif->write)(regaddr, pdata, len, pdev->_serif->user); +} + +ICM_20948_Status_e ICM_20948_execute_r(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len) +{ + if (pdev->_serif->read == NULL) + { + return ICM_20948_Stat_NotImpl; + } + return (*pdev->_serif->read)(regaddr, pdata, len, pdev->_serif->user); +} + +//Transact directly with an I2C device, one byte at a time +//Used to configure a device before it is setup into a normal 0-3 peripheral slot +ICM_20948_Status_e ICM_20948_i2c_controller_periph4_txn(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr) +{ + // Thanks MikeFair! // https://github.com/kriswiner/MPU9250/issues/86 + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + addr = (((Rw) ? 0x80 : 0x00) | addr); + + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_ADDR, (uint8_t *)&addr, 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_REG, (uint8_t *)®, 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_I2C_PERIPH4_CTRL_t ctrl; + ctrl.EN = 1; + ctrl.INT_EN = false; + ctrl.DLY = 0; + ctrl.REG_DIS = !send_reg_addr; + + ICM_20948_I2C_MST_STATUS_t i2c_mst_status; + bool txn_failed = false; + uint16_t nByte = 0; + + while (nByte < len) + { + if (!Rw) + { + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_DO, (uint8_t *)&(data[nByte]), 1); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + // Kick off txn + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_PERIPH4_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_PERIPH4_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // long tsTimeout = millis() + 3000; // Emergency timeout for txn (hard coded to 3 secs) + uint32_t max_cycles = 1000; + uint32_t count = 0; + bool peripheral4Done = false; + while (!peripheral4Done) + { + retval = ICM_20948_set_bank(pdev, 0); + retval = ICM_20948_execute_r(pdev, AGB0_REG_I2C_MST_STATUS, (uint8_t *)&i2c_mst_status, 1); + + peripheral4Done = (i2c_mst_status.I2C_PERIPH4_DONE /*| (millis() > tsTimeout) */); //Avoid forever-loops + peripheral4Done |= (count >= max_cycles); + count++; + } + txn_failed = (i2c_mst_status.I2C_PERIPH4_NACK /*| (millis() > tsTimeout) */); + txn_failed |= (count >= max_cycles); + if (txn_failed) + break; + + if (Rw) + { + retval = ICM_20948_set_bank(pdev, 3); + retval = ICM_20948_execute_r(pdev, AGB3_REG_I2C_PERIPH4_DI, &data[nByte], 1); + } + + nByte++; + } + + if (txn_failed) + { + //We often fail here if mag is stuck + return ICM_20948_Stat_Err; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_single_w(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data) +{ + return ICM_20948_i2c_controller_periph4_txn(pdev, addr, reg, data, 1, false, true); +} + +ICM_20948_Status_e ICM_20948_i2c_master_single_r(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data) +{ + return ICM_20948_i2c_controller_periph4_txn(pdev, addr, reg, data, 1, true, true); +} + +ICM_20948_Status_e ICM_20948_set_bank(ICM_20948_Device_t *pdev, uint8_t bank) +{ + if (bank > 3) + { + return ICM_20948_Stat_ParamErr; + } // Only 4 possible banks + + if (bank == pdev->_last_bank) // Do we need to change bank? + return ICM_20948_Stat_Ok; // Bail if we don't need to change bank to avoid unnecessary bus traffic + + pdev->_last_bank = bank; // Store the requested bank (before we bit-shift) + bank = (bank << 4) & 0x30; // bits 5:4 of REG_BANK_SEL + return ICM_20948_execute_w(pdev, REG_BANK_SEL, &bank, 1); +} + +ICM_20948_Status_e ICM_20948_sw_reset(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + reg.DEVICE_RESET = 1; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_sleep(ICM_20948_Device_t *pdev, bool on) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (on) + { + reg.SLEEP = 1; + } + else + { + reg.SLEEP = 0; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_low_power(ICM_20948_Device_t *pdev, bool on) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (on) + { + reg.LP_EN = 1; + } + else + { + reg.LP_EN = 0; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_clock_source(ICM_20948_Device_t *pdev, ICM_20948_PWR_MGMT_1_CLKSEL_e source) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_PWR_MGMT_1_t reg; + + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + retval = ICM_20948_execute_r(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + reg.CLKSEL = source; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_PWR_MGMT_1, (uint8_t *)®, sizeof(ICM_20948_PWR_MGMT_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_get_who_am_i(ICM_20948_Device_t *pdev, uint8_t *whoami) +{ + if (whoami == NULL) + { + return ICM_20948_Stat_ParamErr; + } + ICM_20948_set_bank(pdev, 0); // Must be in the right bank + return ICM_20948_execute_r(pdev, AGB0_REG_WHO_AM_I, whoami, 1); +} + +ICM_20948_Status_e ICM_20948_check_id(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + uint8_t whoami = 0x00; + retval = ICM_20948_get_who_am_i(pdev, &whoami); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (whoami != ICM_20948_WHOAMI) + { + return ICM_20948_Stat_WrongID; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_data_ready(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_INT_STATUS_1_t reg; + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_STATUS_1, (uint8_t *)®, sizeof(ICM_20948_INT_STATUS_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (!reg.RAW_DATA_0_RDY_INT) + { + retval = ICM_20948_Stat_NoData; + } + return retval; +} + +// Interrupt Configuration +ICM_20948_Status_e ICM_20948_int_pin_cfg(ICM_20948_Device_t *pdev, ICM_20948_INT_PIN_CFG_t *write, ICM_20948_INT_PIN_CFG_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (write != NULL) + { // write first, if available + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)write, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + if (read != NULL) + { // then read, to allow for verification + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)read, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + return retval; +} + +ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_enable_t *write, ICM_20948_INT_enable_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_INT_ENABLE_t en_0; + ICM_20948_INT_ENABLE_1_t en_1; + ICM_20948_INT_ENABLE_2_t en_2; + ICM_20948_INT_ENABLE_3_t en_3; + + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + + if (write != NULL) + { // If the write pointer is not NULL then write to the registers BEFORE reading + en_0.I2C_MST_INT_EN = write->I2C_MST_INT_EN; + en_0.DMP_INT1_EN = write->DMP_INT1_EN; + en_0.PLL_READY_EN = write->PLL_RDY_EN; + en_0.WOM_INT_EN = write->WOM_INT_EN; + en_0.reserved_0 = 0; // Clear RAM garbage + en_0.REG_WOF_EN = write->REG_WOF_EN; + en_1.RAW_DATA_0_RDY_EN = write->RAW_DATA_0_RDY_EN; + en_1.reserved_0 = 0; // Clear RAM garbage + en_2.individual.FIFO_OVERFLOW_EN_4 = write->FIFO_OVERFLOW_EN_4; + en_2.individual.FIFO_OVERFLOW_EN_3 = write->FIFO_OVERFLOW_EN_3; + en_2.individual.FIFO_OVERFLOW_EN_2 = write->FIFO_OVERFLOW_EN_2; + en_2.individual.FIFO_OVERFLOW_EN_1 = write->FIFO_OVERFLOW_EN_1; + en_2.individual.FIFO_OVERFLOW_EN_0 = write->FIFO_OVERFLOW_EN_0; + en_2.individual.reserved_0 = 0; // Clear RAM garbage + en_3.individual.FIFO_WM_EN_4 = write->FIFO_WM_EN_4; + en_3.individual.FIFO_WM_EN_3 = write->FIFO_WM_EN_3; + en_3.individual.FIFO_WM_EN_2 = write->FIFO_WM_EN_2; + en_3.individual.FIFO_WM_EN_1 = write->FIFO_WM_EN_1; + en_3.individual.FIFO_WM_EN_0 = write->FIFO_WM_EN_0; + en_3.individual.reserved_0 = 0; // Clear RAM garbage + + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE, (uint8_t *)&en_0, sizeof(ICM_20948_INT_ENABLE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_1, (uint8_t *)&en_1, sizeof(ICM_20948_INT_ENABLE_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_2, (uint8_t *)&en_2, sizeof(ICM_20948_INT_ENABLE_2_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_ENABLE_3, (uint8_t *)&en_3, sizeof(ICM_20948_INT_ENABLE_3_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + if (read != NULL) + { // If read pointer is not NULL then read the registers (if write is not NULL then this should read back the results of write into read) + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE, (uint8_t *)&en_0, sizeof(ICM_20948_INT_ENABLE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_1, (uint8_t *)&en_1, sizeof(ICM_20948_INT_ENABLE_1_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_2, (uint8_t *)&en_2, sizeof(ICM_20948_INT_ENABLE_2_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_ENABLE_3, (uint8_t *)&en_3, sizeof(ICM_20948_INT_ENABLE_3_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + read->I2C_MST_INT_EN = en_0.I2C_MST_INT_EN; + read->DMP_INT1_EN = en_0.DMP_INT1_EN; + read->PLL_RDY_EN = en_0.PLL_READY_EN; + read->WOM_INT_EN = en_0.WOM_INT_EN; + read->REG_WOF_EN = en_0.REG_WOF_EN; + read->RAW_DATA_0_RDY_EN = en_1.RAW_DATA_0_RDY_EN; + read->FIFO_OVERFLOW_EN_4 = en_2.individual.FIFO_OVERFLOW_EN_4; + read->FIFO_OVERFLOW_EN_3 = en_2.individual.FIFO_OVERFLOW_EN_3; + read->FIFO_OVERFLOW_EN_2 = en_2.individual.FIFO_OVERFLOW_EN_2; + read->FIFO_OVERFLOW_EN_1 = en_2.individual.FIFO_OVERFLOW_EN_1; + read->FIFO_OVERFLOW_EN_0 = en_2.individual.FIFO_OVERFLOW_EN_0; + read->FIFO_WM_EN_4 = en_3.individual.FIFO_WM_EN_4; + read->FIFO_WM_EN_3 = en_3.individual.FIFO_WM_EN_3; + read->FIFO_WM_EN_2 = en_3.individual.FIFO_WM_EN_2; + read->FIFO_WM_EN_1 = en_3.individual.FIFO_WM_EN_1; + read->FIFO_WM_EN_0 = en_3.individual.FIFO_WM_EN_0; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_ACCEL_WOM_THR_t thr; + + retval = ICM_20948_set_bank(pdev, 2); // Must be in the right bank + + if (write != NULL) + { // If the write pointer is not NULL then write to the registers BEFORE reading + thr.WOM_THRESHOLD = write->WOM_THRESHOLD; + + retval = ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_WOM_THR, (uint8_t *)&thr, sizeof(ICM_20948_ACCEL_WOM_THR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + if (read != NULL) + { // If read pointer is not NULL then read the registers (if write is not NULL then this should read back the results of write into read) + retval = ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_WOM_THR, (uint8_t *)&thr, sizeof(ICM_20948_ACCEL_WOM_THR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + read->WOM_THRESHOLD = thr.WOM_THRESHOLD; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_set_sample_mode(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_LP_CONFIG_CYCLE_e mode) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + ICM_20948_LP_CONFIG_t reg; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr | ICM_20948_Internal_Mst))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + retval = ICM_20948_set_bank(pdev, 0); // Must be in the right bank + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_LP_CONFIG, (uint8_t *)®, sizeof(ICM_20948_LP_CONFIG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (sensors & ICM_20948_Internal_Acc) + { + reg.ACCEL_CYCLE = mode; + } // Set all desired sensors to this setting + if (sensors & ICM_20948_Internal_Gyr) + { + reg.GYRO_CYCLE = mode; + } + if (sensors & ICM_20948_Internal_Mst) + { + reg.I2C_MST_CYCLE = mode; + } + + retval = ICM_20948_execute_w(pdev, AGB0_REG_LP_CONFIG, (uint8_t *)®, sizeof(ICM_20948_LP_CONFIG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_full_scale(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_fss_t fss) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + reg.ACCEL_FS_SEL = fss.a; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + reg.GYRO_FS_SEL = fss.g; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_dlpf_cfg(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_dlpcfg_t cfg) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + reg.ACCEL_DLPFCFG = cfg.a; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + reg.GYRO_DLPFCFG = cfg.g; + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + } + return retval; +} + +ICM_20948_Status_e ICM_20948_enable_dlpf(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + ICM_20948_ACCEL_CONFIG_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + if (enable) + { + reg.ACCEL_FCHOICE = 1; + } + else + { + reg.ACCEL_FCHOICE = 0; + } + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_CONFIG, (uint8_t *)®, sizeof(ICM_20948_ACCEL_CONFIG_t)); + } + if (sensors & ICM_20948_Internal_Gyr) + { + ICM_20948_GYRO_CONFIG_1_t reg; + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + retval |= ICM_20948_execute_r(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + if (enable) + { + reg.GYRO_FCHOICE = 1; + } + else + { + reg.GYRO_FCHOICE = 0; + } + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_CONFIG_1, (uint8_t *)®, sizeof(ICM_20948_GYRO_CONFIG_1_t)); + } + return retval; +} + +ICM_20948_Status_e ICM_20948_set_sample_rate(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_smplrt_t smplrt) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + if (!(sensors & (ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr))) + { + return ICM_20948_Stat_SensorNotSupported; + } + + if (sensors & ICM_20948_Internal_Acc) + { + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + uint8_t div1 = (smplrt.a << 8); + uint8_t div2 = (smplrt.a & 0xFF); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_SMPLRT_DIV_1, &div1, 1); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_ACCEL_SMPLRT_DIV_2, &div2, 1); + } + if (sensors & ICM_20948_Internal_Gyr) + { + retval |= ICM_20948_set_bank(pdev, 2); // Must be in the right bank + uint8_t div = (smplrt.g); + retval |= ICM_20948_execute_w(pdev, AGB2_REG_GYRO_SMPLRT_DIV, &div, 1); + } + return retval; +} + +// Interface Things +ICM_20948_Status_e ICM_20948_i2c_master_passthrough(ICM_20948_Device_t *pdev, bool passthrough) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_INT_PIN_CFG_t reg; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)®, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + reg.BYPASS_EN = passthrough; + retval = ICM_20948_execute_w(pdev, AGB0_REG_INT_PIN_CONFIG, (uint8_t *)®, sizeof(ICM_20948_INT_PIN_CFG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_enable(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + // Disable BYPASS_EN + retval = ICM_20948_i2c_master_passthrough(pdev, false); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_I2C_MST_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 3); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB3_REG_I2C_MST_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_MST_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + ctrl.I2C_MST_CLK = 0x07; // corresponds to 345.6 kHz, good for up to 400 kHz + ctrl.I2C_MST_P_NSR = 1; + retval = ICM_20948_execute_w(pdev, AGB3_REG_I2C_MST_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_MST_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ICM_20948_USER_CTRL_t reg; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)®, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + if (enable) + { + reg.I2C_MST_EN = 1; + } + else + { + reg.I2C_MST_EN = 0; + } + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)®, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_master_reset(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.I2C_MST_RST = 1; //Reset! + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_i2c_controller_configure_peripheral(ICM_20948_Device_t *pdev, uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + uint8_t periph_addr_reg; + uint8_t periph_reg_reg; + uint8_t periph_ctrl_reg; + uint8_t periph_do_reg; + + switch (peripheral) + { + case 0: + periph_addr_reg = AGB3_REG_I2C_PERIPH0_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH0_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH0_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH0_DO; + break; + case 1: + periph_addr_reg = AGB3_REG_I2C_PERIPH1_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH1_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH1_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH1_DO; + break; + case 2: + periph_addr_reg = AGB3_REG_I2C_PERIPH2_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH2_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH2_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH2_DO; + break; + case 3: + periph_addr_reg = AGB3_REG_I2C_PERIPH3_ADDR; + periph_reg_reg = AGB3_REG_I2C_PERIPH3_REG; + periph_ctrl_reg = AGB3_REG_I2C_PERIPH3_CTRL; + periph_do_reg = AGB3_REG_I2C_PERIPH3_DO; + break; + default: + return ICM_20948_Stat_ParamErr; + } + + retval = ICM_20948_set_bank(pdev, 3); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // Set the peripheral address and the Rw flag + ICM_20948_I2C_PERIPHX_ADDR_t address; + address.ID = addr; + if (Rw) + { + address.RNW = 1; + } + else + { + address.RNW = 0; // Make sure bit is clear (just in case there is any garbage in that RAM location) + } + retval = ICM_20948_execute_w(pdev, periph_addr_reg, (uint8_t *)&address, sizeof(ICM_20948_I2C_PERIPHX_ADDR_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // If we are setting up a write, configure the Data Out register too + if (!Rw) + { + ICM_20948_I2C_PERIPHX_DO_t dataOutByte; + dataOutByte.DO = dataOut; + retval = ICM_20948_execute_w(pdev, periph_do_reg, (uint8_t *)&dataOutByte, sizeof(ICM_20948_I2C_PERIPHX_DO_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + } + + // Set the peripheral sub-address (register address) + ICM_20948_I2C_PERIPHX_REG_t subaddress; + subaddress.REG = reg; + retval = ICM_20948_execute_w(pdev, periph_reg_reg, (uint8_t *)&subaddress, sizeof(ICM_20948_I2C_PERIPHX_REG_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + // Set up the control info + ICM_20948_I2C_PERIPHX_CTRL_t ctrl; + ctrl.LENG = len; + ctrl.EN = enable; + ctrl.REG_DIS = data_only; + ctrl.GRP = grp; + ctrl.BYTE_SW = swap; + retval = ICM_20948_execute_w(pdev, periph_ctrl_reg, (uint8_t *)&ctrl, sizeof(ICM_20948_I2C_PERIPHX_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +// Higher Level +ICM_20948_Status_e ICM_20948_get_agmt(ICM_20948_Device_t *pdev, ICM_20948_AGMT_t *pagmt) +{ + if (pagmt == NULL) + { + return ICM_20948_Stat_ParamErr; + } + + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + const uint8_t numbytes = 14 + 9; //Read Accel, gyro, temp, and 9 bytes of mag + uint8_t buff[numbytes]; + + // Get readings + retval |= ICM_20948_set_bank(pdev, 0); + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB0_REG_ACCEL_XOUT_H, buff, numbytes); + + pagmt->acc.axes.x = ((buff[0] << 8) | (buff[1] & 0xFF)); + pagmt->acc.axes.y = ((buff[2] << 8) | (buff[3] & 0xFF)); + pagmt->acc.axes.z = ((buff[4] << 8) | (buff[5] & 0xFF)); + + pagmt->gyr.axes.x = ((buff[6] << 8) | (buff[7] & 0xFF)); + pagmt->gyr.axes.y = ((buff[8] << 8) | (buff[9] & 0xFF)); + pagmt->gyr.axes.z = ((buff[10] << 8) | (buff[11] & 0xFF)); + + pagmt->tmp.val = ((buff[12] << 8) | (buff[13] & 0xFF)); + + pagmt->magStat1 = buff[14]; + pagmt->mag.axes.x = ((buff[16] << 8) | (buff[15] & 0xFF)); //Mag data is read little endian + pagmt->mag.axes.y = ((buff[18] << 8) | (buff[17] & 0xFF)); + pagmt->mag.axes.z = ((buff[20] << 8) | (buff[19] & 0xFF)); + pagmt->magStat2 = buff[22]; + + // Get settings to be able to compute scaled values + retval |= ICM_20948_set_bank(pdev, 2); + ICM_20948_ACCEL_CONFIG_t acfg; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_ACCEL_CONFIG, (uint8_t *)&acfg, 1 * sizeof(acfg)); + pagmt->fss.a = acfg.ACCEL_FS_SEL; // Worth noting that without explicitly setting the FS range of the accelerometer it was showing the register value for +/- 2g but the reported values were actually scaled to the +/- 16g range + // Wait a minute... now it seems like this problem actually comes from the digital low-pass filter. When enabled the value is 1/8 what it should be... + retval |= ICM_20948_set_bank(pdev, 2); + ICM_20948_GYRO_CONFIG_1_t gcfg1; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_GYRO_CONFIG_1, (uint8_t *)&gcfg1, 1 * sizeof(gcfg1)); + pagmt->fss.g = gcfg1.GYRO_FS_SEL; + ICM_20948_ACCEL_CONFIG_2_t acfg2; + retval |= ICM_20948_execute_r(pdev, (uint8_t)AGB2_REG_ACCEL_CONFIG_2, (uint8_t *)&acfg2, 1 * sizeof(acfg2)); + + return retval; +} + +// FIFO + +ICM_20948_Status_e ICM_20948_enable_FIFO(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (enable) + ctrl.FIFO_EN = 1; + else + ctrl.FIFO_EN = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_reset_FIFO(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_RST_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.FIFO_RESET = 0x1F; // Datasheet says "FIFO_RESET[4:0]" + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + //delay ??? + + ctrl.FIFO_RESET = 0x1E; // The InvenSense Nucleo examples write 0x1F followed by 0x1E + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_RST, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_RST_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +ICM_20948_Status_e ICM_20948_set_FIFO_mode(ICM_20948_Device_t *pdev, bool snapshot) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_MODE_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_MODE, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_MODE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (snapshot) + ctrl.FIFO_MODE = 0x1F; // Datasheet says "FIFO_MODE[4:0]" + else + ctrl.FIFO_MODE = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_FIFO_MODE, (uint8_t *)&ctrl, sizeof(ICM_20948_FIFO_MODE_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_get_FIFO_count(ICM_20948_Device_t *pdev, uint16_t *count) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_FIFO_COUNTH_t ctrlh; + ICM_20948_FIFO_COUNTL_t ctrll; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_COUNT_H, (uint8_t *)&ctrlh, sizeof(ICM_20948_FIFO_COUNTH_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrlh.FIFO_COUNTH &= 0x1F; // Datasheet says "FIFO_CNT[12:8]" + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_COUNT_L, (uint8_t *)&ctrll, sizeof(ICM_20948_FIFO_COUNTL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + *count = (((uint16_t)ctrlh.FIFO_COUNTH) << 8) | (uint16_t)ctrll.FIFO_COUNTL; + + return retval; +} + +ICM_20948_Status_e ICM_20948_read_FIFO(ICM_20948_Device_t *pdev, uint8_t *data, uint8_t len) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_FIFO_R_W, data, len); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + return retval; +} + +// DMP + +ICM_20948_Status_e ICM_20948_enable_DMP(ICM_20948_Device_t *pdev, bool enable) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + if (enable) + ctrl.DMP_EN = 1; + else + ctrl.DMP_EN = 0; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_reset_DMP(ICM_20948_Device_t *pdev) +{ + ICM_20948_Status_e retval = ICM_20948_Stat_Ok; + + ICM_20948_USER_CTRL_t ctrl; + retval = ICM_20948_set_bank(pdev, 0); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + retval = ICM_20948_execute_r(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + + ctrl.DMP_RST = 1; + + retval = ICM_20948_execute_w(pdev, AGB0_REG_USER_CTRL, (uint8_t *)&ctrl, sizeof(ICM_20948_USER_CTRL_t)); + if (retval != ICM_20948_Stat_Ok) + { + return retval; + } + return retval; +} + +ICM_20948_Status_e ICM_20948_firmware_load(ICM_20948_Device_t *pdev) +{ +#if defined(ICM_20948_USE_DMP) + return (inv_icm20948_firmware_load(pdev, dmp3_image, sizeof(dmp3_image), DMP_LOAD_START)); +#else + return ICM_20948_Stat_DMPNotSupported; +#endif +} + +/** @brief Loads the DMP firmware from SRAM +* @param[in] data pointer where the image +* @param[in] size size if the image +* @param[in] load_addr address to loading the image +* @return 0 in case of success, -1 for any error +*/ +ICM_20948_Status_e inv_icm20948_firmware_load(ICM_20948_Device_t *pdev, const unsigned char *data_start, unsigned short size_start, unsigned short load_addr) +{ + int write_size; + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned short memaddr; + const unsigned char *data; + unsigned short size; + unsigned char data_cmp[INV_MAX_SERIAL_READ]; + int flag = 0; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + if (pdev->_firmware_loaded) + return ICM_20948_Stat_Ok; // Bail with no error if firmware is already loaded + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write DMP memory + + data = data_start; + size = size_start; + memaddr = load_addr; + #ifdef ICM_20948_USE_PROGMEM_FOR_DMP + unsigned char data_not_pg[INV_MAX_SERIAL_READ]; // Suggested by @HyperKokichi in Issue #63 + #endif + while (size > 0) + { + //write_size = min(size, INV_MAX_SERIAL_WRITE); // Write in chunks of INV_MAX_SERIAL_WRITE + if (size <= INV_MAX_SERIAL_WRITE) // Write in chunks of INV_MAX_SERIAL_WRITE + write_size = size; + else + write_size = INV_MAX_SERIAL_WRITE; + if ((memaddr & 0xff) + write_size > 0x100) + { + // Moved across a bank + write_size = (memaddr & 0xff) + write_size - 0x100; + } +#ifdef ICM_20948_USE_PROGMEM_FOR_DMP + memcpy_P(data_not_pg, data, write_size); // Suggested by @HyperKokichi in Issue #63 + result = inv_icm20948_write_mems(pdev, memaddr, write_size, (unsigned char *)data_not_pg); +#else + result = inv_icm20948_write_mems(pdev, memaddr, write_size, (unsigned char *)data); +#endif + if (result != ICM_20948_Stat_Ok) + return result; + data += write_size; + size -= write_size; + memaddr += write_size; + } + + // Verify DMP memory + + data = data_start; + size = size_start; + memaddr = load_addr; + while (size > 0) + { + //write_size = min(size, INV_MAX_SERIAL_READ); // Read in chunks of INV_MAX_SERIAL_READ + if (size <= INV_MAX_SERIAL_READ) // Read in chunks of INV_MAX_SERIAL_READ + write_size = size; + else + write_size = INV_MAX_SERIAL_READ; + if ((memaddr & 0xff) + write_size > 0x100) + { + // Moved across a bank + write_size = (memaddr & 0xff) + write_size - 0x100; + } + result = inv_icm20948_read_mems(pdev, memaddr, write_size, data_cmp); + if (result != ICM_20948_Stat_Ok) + flag++; // Error, DMP not written correctly +#ifdef ICM_20948_USE_PROGMEM_FOR_DMP + memcpy_P(data_not_pg, data, write_size); // Suggested by @HyperKokichi in Issue #63 + if (memcmp(data_cmp, data_not_pg, write_size)) +#else + if (memcmp(data_cmp, data, write_size)) // Compare the data +#endif + return ICM_20948_Stat_DMPVerifyFail; + data += write_size; + size -= write_size; + memaddr += write_size; + } + + //Enable LP_EN since we disabled it at begining of this function. + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + if (!flag) + { + //Serial.println("DMP Firmware was updated successfully.."); + pdev->_firmware_loaded = true; + } + + return result; +} + +ICM_20948_Status_e ICM_20948_set_dmp_start_address(ICM_20948_Device_t *pdev, unsigned short address) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + unsigned char start_address[2]; + + start_address[0] = (unsigned char)(address >> 8); + start_address[1] = (unsigned char)(address & 0xff); + + // result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + // if (result != ICM_20948_Stat_Ok) + // { + // return result; + // } + // + // result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + // if (result != ICM_20948_Stat_Ok) + // { + // return result; + // } + + result = ICM_20948_set_bank(pdev, 2); // Set bank 2 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write the sensor control bits into memory address AGB2_REG_PRGM_START_ADDRH + result = ICM_20948_execute_w(pdev, AGB2_REG_PRGM_START_ADDRH, (uint8_t *)start_address, 2); + + return result; +} + +/** +* @brief Write data to a register in DMP memory +* @param[in] DMP memory address +* @param[in] number of byte to be written +* @param[out] output data from the register +* @return 0 if successful. +*/ +ICM_20948_Status_e inv_icm20948_write_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, const unsigned char *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned int bytesWritten = 0; + unsigned int thisLen; + unsigned char lBankSelected; + unsigned char lStartAddrSelected; + + if (!data) + { + return ICM_20948_Stat_NoData; + } + + result = ICM_20948_set_bank(pdev, 0); // Set bank 0 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + lBankSelected = (reg >> 8); + + if (lBankSelected != pdev->_last_mems_bank) + { + pdev->_last_mems_bank = lBankSelected; + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_BANK_SEL, &lBankSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + } + + while (bytesWritten < length) + { + lStartAddrSelected = (reg & 0xff); + + /* Sets the starting read or write address for the selected memory, inside of the selected page (see MEM_SEL Register). + Contents are changed after read or write of the selected memory. + This register must be written prior to each access to initialize the register to the proper starting address. + The address will auto increment during burst transactions. Two consecutive bursts without re-initializing the start address would skip one address. */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_START_ADDR, &lStartAddrSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + if (length - bytesWritten <= INV_MAX_SERIAL_WRITE) + thisLen = length - bytesWritten; + else + thisLen = INV_MAX_SERIAL_WRITE; + + /* Write data */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_R_W, (uint8_t *)&data[bytesWritten], thisLen); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + bytesWritten += thisLen; + reg += thisLen; + } + + return result; +} + +/** +* @brief Read data from a register in DMP memory +* @param[in] DMP memory address +* @param[in] number of byte to be read +* @param[in] input data from the register +* @return 0 if successful. +*/ +ICM_20948_Status_e inv_icm20948_read_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, unsigned char *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + unsigned int bytesRead = 0; + unsigned int thisLen; + unsigned char lBankSelected; + unsigned char lStartAddrSelected; + + if (!data) + { + return ICM_20948_Stat_NoData; + } + + result = ICM_20948_set_bank(pdev, 0); // Set bank 0 + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + lBankSelected = (reg >> 8); + + if (lBankSelected != pdev->_last_mems_bank) + { + pdev->_last_mems_bank = lBankSelected; + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_BANK_SEL, &lBankSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + } + + while (bytesRead < length) + { + lStartAddrSelected = (reg & 0xff); + + /* Sets the starting read or write address for the selected memory, inside of the selected page (see MEM_SEL Register). + Contents are changed after read or write of the selected memory. + This register must be written prior to each access to initialize the register to the proper starting address. + The address will auto increment during burst transactions. Two consecutive bursts without re-initializing the start address would skip one address. */ + + result = ICM_20948_execute_w(pdev, AGB0_REG_MEM_START_ADDR, &lStartAddrSelected, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + if (length - bytesRead <= INV_MAX_SERIAL_READ) + thisLen = length - bytesRead; + else + thisLen = INV_MAX_SERIAL_READ; + + /* Read data */ + + result = ICM_20948_execute_r(pdev, AGB0_REG_MEM_R_W, &data[bytesRead], thisLen); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + bytesRead += thisLen; + reg += thisLen; + } + + return result; +} + +ICM_20948_Status_e inv_icm20948_set_dmp_sensor_period(ICM_20948_Device_t *pdev, enum DMP_ODR_Registers odr_reg, uint16_t interval) +{ + // Set the ODR registers and clear the ODR counter + + // In order to set an ODR for a given sensor data, write 2-byte value to DMP using key defined above for a particular sensor. + // Setting value can be calculated as follows: + // Value = (DMP running rate (225Hz) / ODR ) - 1 + // E.g. For a 25Hz ODR rate, value= (225/25) -1 = 8. + + // During run-time, if an ODR is changed, the corresponding rate counter must be reset. + // To reset, write 2-byte {0,0} to DMP using keys below for a particular sensor: + + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + ICM_20948_Status_e result2 = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + unsigned char odr_reg_val[2]; + odr_reg_val[0] = (unsigned char)(interval >> 8); + odr_reg_val[1] = (unsigned char)(interval & 0xff); + + unsigned char odr_count_zero[2] = {0x00, 0x00}; + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + switch (odr_reg) + { + case DMP_ODR_Reg_Cpass_Calibr: + { + result = inv_icm20948_write_mems(pdev, ODR_CPASS_CALIBR, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_CPASS_CALIBR, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Gyro_Calibr: + { + result = inv_icm20948_write_mems(pdev, ODR_GYRO_CALIBR, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GYRO_CALIBR, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Pressure: + { + result = inv_icm20948_write_mems(pdev, ODR_PRESSURE, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_PRESSURE, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Geomag: + { + result = inv_icm20948_write_mems(pdev, ODR_GEOMAG, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GEOMAG, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_PQuat6: + { + result = inv_icm20948_write_mems(pdev, ODR_PQUAT6, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_PQUAT6, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Quat9: + { + result = inv_icm20948_write_mems(pdev, ODR_QUAT9, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_QUAT9, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Quat6: + { + result = inv_icm20948_write_mems(pdev, ODR_QUAT6, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_QUAT6, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_ALS: + { + result = inv_icm20948_write_mems(pdev, ODR_ALS, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_ALS, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Cpass: + { + result = inv_icm20948_write_mems(pdev, ODR_CPASS, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_CPASS, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Gyro: + { + result = inv_icm20948_write_mems(pdev, ODR_GYRO, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_GYRO, 2, (const unsigned char *)&odr_count_zero); + } + break; + case DMP_ODR_Reg_Accel: + { + result = inv_icm20948_write_mems(pdev, ODR_ACCEL, 2, (const unsigned char *)&odr_reg_val); + result2 = inv_icm20948_write_mems(pdev, ODR_CNTR_ACCEL, 2, (const unsigned char *)&odr_count_zero); + } + break; + default: + result = ICM_20948_Stat_InvalDMPRegister; + break; + } + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + if (result2 > result) + result = result2; // Return the highest error + + return result; +} + +ICM_20948_Status_e inv_icm20948_enable_dmp_sensor(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + uint16_t inv_event_control = 0; // Use this to store the value for MOTION_EVENT_CTL + uint16_t data_rdy_status = 0; // Use this to store the value for DATA_RDY_STATUS + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; // Bail if DMP is not supported + + uint8_t androidSensor = sensor_type_2_android_sensor(sensor); // Convert sensor from enum inv_icm20948_sensor to Android numbering + + if (androidSensor >= ANDROID_SENSOR_NUM_MAX) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported (TO DO: Support B2S etc) + + // Convert the Android sensor into a bit mask for DATA_OUT_CTL1 + uint16_t delta = inv_androidSensor_to_control_bits[androidSensor]; + if (delta == 0xFFFF) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor number into a bitmask and set or clear that bit in _enabled_Android_0 / _enabled_Android_1 + unsigned long androidSensorAsBitMask; + if (androidSensor < 32) // Sensors 0-31 + { + androidSensorAsBitMask = 1L << androidSensor; + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_0 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor + } + else + { + pdev->_enabled_Android_0 |= androidSensorAsBitMask; // Set the bit to enable the sensor + } + } + else // Sensors 32- + { + androidSensorAsBitMask = 1L << (androidSensor - 32); + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_1 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor + } + else + { + pdev->_enabled_Android_1 |= androidSensorAsBitMask; // Set the bit to enable the sensor + } + } + + // Now we know androidSensor is valid, reconstruct the value for DATA_OUT_CTL1 from _enabled_Android_0 and _enabled_Android_0 + delta = 0; // Clear delta + for (int i = 0; i < 32; i++) + { + androidSensorAsBitMask = 1L << i; + if ((pdev->_enabled_Android_0 & androidSensorAsBitMask) > 0) // Check if the Android sensor (0-31) is enabled + { + delta |= inv_androidSensor_to_control_bits[i]; // If it is, or the required bits into delta + } + if ((pdev->_enabled_Android_1 & androidSensorAsBitMask) > 0) // Check if the Android sensor (32-) is enabled + { + delta |= inv_androidSensor_to_control_bits[i + 32]; // If it is, or the required bits into delta + } + // Also check which bits need to be set in the Data Ready Status and Motion Event Control registers + // Compare to INV_NEEDS_ACCEL_MASK, INV_NEEDS_GYRO_MASK and INV_NEEDS_COMPASS_MASK + if (((androidSensorAsBitMask & INV_NEEDS_ACCEL_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_ACCEL_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Accel; + inv_event_control |= DMP_Motion_Event_Control_Accel_Calibr; + } + if (((androidSensorAsBitMask & INV_NEEDS_GYRO_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_GYRO_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Gyro; + inv_event_control |= DMP_Motion_Event_Control_Gyro_Calibr; + } + if (((androidSensorAsBitMask & INV_NEEDS_COMPASS_MASK) > 0) || ((androidSensorAsBitMask & INV_NEEDS_COMPASS_MASK1) > 0)) + { + data_rdy_status |= DMP_Data_ready_Secondary_Compass; + inv_event_control |= DMP_Motion_Event_Control_Compass_Calibr; + } + } + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Check if Accel, Gyro/Gyro_Calibr or Compass_Calibr/Quat9/GeoMag/Compass are to be enabled. If they are then we need to request the accuracy data via header2. + uint16_t delta2 = 0; + if ((delta & DMP_Data_Output_Control_1_Accel) > 0) + { + delta2 |= DMP_Data_Output_Control_2_Accel_Accuracy; + } + if (((delta & DMP_Data_Output_Control_1_Gyro_Calibr) > 0) || ((delta & DMP_Data_Output_Control_1_Gyro) > 0)) + { + delta2 |= DMP_Data_Output_Control_2_Gyro_Accuracy; + } + if (((delta & DMP_Data_Output_Control_1_Compass_Calibr) > 0) || ((delta & DMP_Data_Output_Control_1_Compass) > 0) || ((delta & DMP_Data_Output_Control_1_Quat9) > 0) || ((delta & DMP_Data_Output_Control_1_Geomag) > 0)) + { + delta2 |= DMP_Data_Output_Control_2_Compass_Accuracy; + } + // TO DO: Add DMP_Data_Output_Control_2_Pickup etc. if required + + // Write the sensor control bits into memory address DATA_OUT_CTL1 + unsigned char data_output_control_reg[2]; + data_output_control_reg[0] = (unsigned char)(delta >> 8); + data_output_control_reg[1] = (unsigned char)(delta & 0xff); + pdev->_dataOutCtl1 = delta; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_OUT_CTL1, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Write the 'header2' sensor control bits into memory address DATA_OUT_CTL2 + data_output_control_reg[0] = (unsigned char)(delta2 >> 8); + data_output_control_reg[1] = (unsigned char)(delta2 & 0xff); + pdev->_dataOutCtl2 = delta2; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_OUT_CTL2, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Set the DATA_RDY_STATUS register + data_output_control_reg[0] = (unsigned char)(data_rdy_status >> 8); + data_output_control_reg[1] = (unsigned char)(data_rdy_status & 0xff); + pdev->_dataRdyStatus = data_rdy_status; // Diagnostics + result = inv_icm20948_write_mems(pdev, DATA_RDY_STATUS, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + // Check which extra bits need to be set in the Motion Event Control register + if ((delta & DMP_Data_Output_Control_1_Quat9) > 0) + { + inv_event_control |= DMP_Motion_Event_Control_9axis; + } + if (((delta & DMP_Data_Output_Control_1_Step_Detector) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_0) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_1) > 0) || ((delta & DMP_Data_Output_Control_1_Step_Ind_2) > 0)) + { + inv_event_control |= DMP_Motion_Event_Control_Pedometer_Interrupt; + } + if ((delta & DMP_Data_Output_Control_1_Geomag) > 0) + { + inv_event_control |= DMP_Motion_Event_Control_Geomag; + } + + // Set the MOTION_EVENT_CTL register + data_output_control_reg[0] = (unsigned char)(inv_event_control >> 8); + data_output_control_reg[1] = (unsigned char)(inv_event_control & 0xff); + pdev->_motionEventCtl = inv_event_control; // Diagnostics + result = inv_icm20948_write_mems(pdev, MOTION_EVENT_CTL, 2, (const unsigned char *)&data_output_control_reg); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + return result; +} + +ICM_20948_Status_e inv_icm20948_enable_dmp_sensor_int(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; // Bail if DMP is not supported + + uint8_t androidSensor = sensor_type_2_android_sensor(sensor); // Convert sensor from enum inv_icm20948_sensor to Android numbering + + if (androidSensor > ANDROID_SENSOR_NUM_MAX) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor into a bit mask for DATA_OUT_CTL1 + uint16_t delta = inv_androidSensor_to_control_bits[androidSensor]; + if (delta == 0xFFFF) + return ICM_20948_Stat_SensorNotSupported; // Bail if the sensor is not supported + + // Convert the Android sensor number into a bitmask and set or clear that bit in _enabled_Android_intr_0 / _enabled_Android_intr_1 + unsigned long androidSensorAsBitMask; + if (androidSensor < 32) // Sensors 0-31 + { + androidSensorAsBitMask = 1L << androidSensor; + if (state == 0) // Should we disable the sensor interrupt? + { + pdev->_enabled_Android_intr_0 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor interrupt + } + else + { + pdev->_enabled_Android_intr_0 |= androidSensorAsBitMask; // Set the bit to enable the sensor interrupt + } + } + else // Sensors 32- + { + androidSensorAsBitMask = 1L << (androidSensor - 32); + if (state == 0) // Should we disable the sensor? + { + pdev->_enabled_Android_intr_1 &= ~androidSensorAsBitMask; // Clear the bit to disable the sensor interrupt + } + else + { + pdev->_enabled_Android_intr_1 |= androidSensorAsBitMask; // Set the bit to enable the sensor interrupt + } + } + + // Now we know androidSensor is valid, reconstruct the value for DATA_INTR_CTL from _enabled_Android_intr_0 and _enabled_Android_intr_0 + delta = 0; // Clear delta + for (int i = 0; i < 32; i++) + { + androidSensorAsBitMask = 1L << i; + if ((pdev->_enabled_Android_intr_0 & androidSensorAsBitMask) > 0) // Check if the Android sensor (0-31) interrupt is enabled + { + delta |= inv_androidSensor_to_control_bits[i]; // If it is, or the required bits into delta + } + if ((pdev->_enabled_Android_intr_1 & androidSensorAsBitMask) > 0) // Check if the Android sensor (32-) interrupt is enabled + { + delta |= inv_androidSensor_to_control_bits[i + 32]; // If it is, or the required bits into delta + } + } + + result = ICM_20948_sleep(pdev, false); // Make sure chip is awake + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + result = ICM_20948_low_power(pdev, false); // Make sure chip is not in low power state + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + unsigned char data_intr_ctl[2]; + + data_intr_ctl[0] = (unsigned char)(delta >> 8); + data_intr_ctl[1] = (unsigned char)(delta & 0xff); + pdev->_dataIntrCtl = delta; // Diagnostics + + // Write the interrupt control bits into memory address DATA_INTR_CTL + result = inv_icm20948_write_mems(pdev, DATA_INTR_CTL, 2, (const unsigned char *)&data_intr_ctl); + + result = ICM_20948_low_power(pdev, true); // Put chip into low power state + if (result != ICM_20948_Stat_Ok) + return result; + + return result; +} + +ICM_20948_Status_e inv_icm20948_read_dmp_data(ICM_20948_Device_t *pdev, icm_20948_DMP_data_t *data) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + uint8_t fifoBytes[icm_20948_DMP_Maximum_Bytes]; // Interim storage for the FIFO data + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + // Check how much data is in the FIFO + uint16_t fifo_count; + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + + if (fifo_count < icm_20948_DMP_Header_Bytes) // Has a 2-byte header arrived? + return ICM_20948_Stat_FIFONoDataAvail; // Bail if no header is available + + // Read the header (2 bytes) + data->header = 0; // Clear the existing header + uint16_t aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Header_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Header_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->header = aShort; // Store the header in data->header + fifo_count -= icm_20948_DMP_Header_Bytes; // Decrement the count + + // If the header indicates a header2 is present then read that now + data->header2 = 0; // Clear the existing header2 + if ((data->header & DMP_header_bitmap_Header2) > 0) // If the header2 bit is set + { + if (fifo_count < icm_20948_DMP_Header2_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Header2_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if no header2 is available + // Read the header (2 bytes) + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Header2_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Header2_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->header2 = aShort; // Store the header2 in data->header2 + fifo_count -= icm_20948_DMP_Header2_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Accel) > 0) // case DMP_header_bitmap_Accel: + { + if (fifo_count < icm_20948_DMP_Raw_Accel_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Raw_Accel_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Raw_Accel_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Raw_Accel_Bytes; i++) + { + data->Raw_Accel.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Raw_Accel_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Gyro) > 0) // case DMP_header_bitmap_Gyro: + { + if (fifo_count < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes)); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes); i++) + { + data->Raw_Gyro.Bytes[DMP_Raw_Gyro_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= (icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes); // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Compass) > 0) // case DMP_header_bitmap_Compass: + { + if (fifo_count < icm_20948_DMP_Compass_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Bytes; i++) + { + data->Compass.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Compass_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_ALS) > 0) // case DMP_header_bitmap_ALS: + { + if (fifo_count < icm_20948_DMP_ALS_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_ALS_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_ALS_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_ALS_Bytes; i++) + { + data->ALS[i] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_ALS_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Quat6) > 0) // case DMP_header_bitmap_Quat6: + { + if (fifo_count < icm_20948_DMP_Quat6_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Quat6_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Quat6_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Quat6_Bytes; i++) + { + data->Quat6.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Quat6_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Quat9) > 0) // case DMP_header_bitmap_Quat9: + { + if (fifo_count < icm_20948_DMP_Quat9_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Quat9_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Quat9_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Quat9_Bytes; i++) + { + data->Quat9.Bytes[DMP_Quat9_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Quat9_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_PQuat6) > 0) // case DMP_header_bitmap_PQuat6: + { + if (fifo_count < icm_20948_DMP_PQuat6_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_PQuat6_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_PQuat6_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_PQuat6_Bytes; i++) + { + data->PQuat6.Bytes[DMP_PQuat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_PQuat6_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Geomag) > 0) // case DMP_header_bitmap_Geomag: + { + if (fifo_count < icm_20948_DMP_Geomag_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Geomag_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Geomag_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Geomag_Bytes; i++) + { + data->Geomag.Bytes[DMP_Quat9_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Geomag_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Pressure) > 0) // case DMP_header_bitmap_Pressure: + { + if (fifo_count < icm_20948_DMP_Pressure_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Pressure_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Pressure_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Pressure_Bytes; i++) + { + data->Pressure[i] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Pressure_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Gyro_Calibr) > 0) // case DMP_header_bitmap_Gyro_Calibr: + { + // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Gyro_Calibr_Bytes is not supported + // and looking at DMP frames which have the Gyro_Calibr bit set, that certainly seems to be true. + // So, we'll skip this...: + /* + if (fifo_count < icm_20948_DMP_Gyro_Calibr_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Gyro_Calibr_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Gyro_Calibr_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Gyro_Calibr_Bytes; i++) + { + data->Gyro_Calibr.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Gyro_Calibr_Bytes; // Decrement the count + */ + } + + if ((data->header & DMP_header_bitmap_Compass_Calibr) > 0) // case DMP_header_bitmap_Compass_Calibr: + { + if (fifo_count < icm_20948_DMP_Compass_Calibr_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Calibr_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Calibr_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Calibr_Bytes; i++) + { + data->Compass_Calibr.Bytes[DMP_Quat6_Byte_Ordering[i]] = fifoBytes[i]; // Correct the byte order (map big endian to little endian) + } + fifo_count -= icm_20948_DMP_Compass_Calibr_Bytes; // Decrement the count + } + + if ((data->header & DMP_header_bitmap_Step_Detector) > 0) // case DMP_header_bitmap_Step_Detector: + { + if (fifo_count < icm_20948_DMP_Step_Detector_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Step_Detector_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Step_Detector_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + uint32_t aWord = 0; + for (int i = 0; i < icm_20948_DMP_Step_Detector_Bytes; i++) + { + aWord |= ((uint32_t)fifoBytes[i]) << (24 - (i * 8)); + } + data->Pedometer_Timestamp = aWord; + fifo_count -= icm_20948_DMP_Step_Detector_Bytes; // Decrement the count + } + + // Now check for header2 features + + if ((data->header2 & DMP_header2_bitmap_Accel_Accuracy) > 0) // case DMP_header2_bitmap_Accel_Accuracy: + { + if (fifo_count < icm_20948_DMP_Accel_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Accel_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Accel_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Accel_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Accel_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Accel_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Gyro_Accuracy) > 0) // case DMP_header2_bitmap_Gyro_Accuracy: + { + if (fifo_count < icm_20948_DMP_Gyro_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Gyro_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Gyro_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Gyro_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Gyro_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Gyro_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Compass_Accuracy) > 0) // case DMP_header2_bitmap_Compass_Accuracy: + { + if (fifo_count < icm_20948_DMP_Compass_Accuracy_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Compass_Accuracy_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Compass_Accuracy_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Compass_Accuracy_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Compass_Accuracy = aShort; + fifo_count -= icm_20948_DMP_Compass_Accuracy_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Fsync) > 0) // case DMP_header2_bitmap_Fsync: + { + // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Fsync_Detection_Bytes is not supported. + // So, we'll skip this just in case...: + /* + if (fifo_count < icm_20948_DMP_Fsync_Detection_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Fsync_Detection_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Fsync_Detection_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Fsync_Detection_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Fsync_Delay_Time = aShort; + fifo_count -= icm_20948_DMP_Fsync_Detection_Bytes; // Decrement the count + */ + } + + if ((data->header2 & DMP_header2_bitmap_Pickup) > 0) // case DMP_header2_bitmap_Pickup: + { + if (fifo_count < icm_20948_DMP_Pickup_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Pickup_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Pickup_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Pickup_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Pickup = aShort; + fifo_count -= icm_20948_DMP_Pickup_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Activity_Recog) > 0) // case DMP_header2_bitmap_Activity_Recog: + { + if (fifo_count < icm_20948_DMP_Activity_Recognition_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Activity_Recognition_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Activity_Recognition_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Activity_Recognition_Bytes; i++) + { + data->Activity_Recognition.Bytes[DMP_Activity_Recognition_Byte_Ordering[i]] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Activity_Recognition_Bytes; // Decrement the count + } + + if ((data->header2 & DMP_header2_bitmap_Secondary_On_Off) > 0) // case DMP_header2_bitmap_Secondary_On_Off: + { + if (fifo_count < icm_20948_DMP_Secondary_On_Off_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Secondary_On_Off_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Secondary_On_Off_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Secondary_On_Off_Bytes; i++) + { + data->Secondary_On_Off.Bytes[DMP_Secondary_On_Off_Byte_Ordering[i]] = fifoBytes[i]; + } + fifo_count -= icm_20948_DMP_Secondary_On_Off_Bytes; // Decrement the count + } + + // Finally, extract the footer (gyro count) + if (fifo_count < icm_20948_DMP_Footer_Bytes) // Check if we need to read the FIFO count again + { + result = ICM_20948_get_FIFO_count(pdev, &fifo_count); + if (result != ICM_20948_Stat_Ok) + return result; + } + if (fifo_count < icm_20948_DMP_Footer_Bytes) + return ICM_20948_Stat_FIFOIncompleteData; // Bail if not enough data is available + aShort = 0; + result = ICM_20948_read_FIFO(pdev, &fifoBytes[0], icm_20948_DMP_Footer_Bytes); + if (result != ICM_20948_Stat_Ok) + return result; + for (int i = 0; i < icm_20948_DMP_Footer_Bytes; i++) + { + aShort |= ((uint16_t)fifoBytes[i]) << (8 - (i * 8)); + } + data->Footer = aShort; + fifo_count -= icm_20948_DMP_Footer_Bytes; // Decrement the count + + if (fifo_count > 0) // Check if there is still data waiting to be read + return ICM_20948_Stat_FIFOMoreDataAvail; + + return result; +} + +static uint8_t sensor_type_2_android_sensor(enum inv_icm20948_sensor sensor) +{ + switch (sensor) + { + case INV_ICM20948_SENSOR_ACCELEROMETER: + return ANDROID_SENSOR_ACCELEROMETER; // 1 + case INV_ICM20948_SENSOR_GYROSCOPE: + return ANDROID_SENSOR_GYROSCOPE; // 4 + case INV_ICM20948_SENSOR_RAW_ACCELEROMETER: + return ANDROID_SENSOR_RAW_ACCELEROMETER; // 42 + case INV_ICM20948_SENSOR_RAW_GYROSCOPE: + return ANDROID_SENSOR_RAW_GYROSCOPE; // 43 + case INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED: + return ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED; // 14 + case INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED: + return ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED; // 16 + case INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON: + return ANDROID_SENSOR_ACTIVITY_CLASSIFICATON; // 47 + case INV_ICM20948_SENSOR_STEP_DETECTOR: + return ANDROID_SENSOR_STEP_DETECTOR; // 18 + case INV_ICM20948_SENSOR_STEP_COUNTER: + return ANDROID_SENSOR_STEP_COUNTER; // 19 + case INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR: + return ANDROID_SENSOR_GAME_ROTATION_VECTOR; // 15 + case INV_ICM20948_SENSOR_ROTATION_VECTOR: + return ANDROID_SENSOR_ROTATION_VECTOR; // 11 + case INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR: + return ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR; // 20 + case INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD: + return ANDROID_SENSOR_GEOMAGNETIC_FIELD; // 2 + case INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION: + return ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION; // 17 + case INV_ICM20948_SENSOR_FLIP_PICKUP: + return ANDROID_SENSOR_FLIP_PICKUP; // 46 + case INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR: + return ANDROID_SENSOR_WAKEUP_TILT_DETECTOR; // 41 + case INV_ICM20948_SENSOR_GRAVITY: + return ANDROID_SENSOR_GRAVITY; // 9 + case INV_ICM20948_SENSOR_LINEAR_ACCELERATION: + return ANDROID_SENSOR_LINEAR_ACCELERATION; // 10 + case INV_ICM20948_SENSOR_ORIENTATION: + return ANDROID_SENSOR_ORIENTATION; // 3 + case INV_ICM20948_SENSOR_B2S: + return ANDROID_SENSOR_B2S; // 45 + default: + return ANDROID_SENSOR_NUM_MAX; + } +} + +enum inv_icm20948_sensor inv_icm20948_sensor_android_2_sensor_type(int sensor) +{ + switch (sensor) + { + case ANDROID_SENSOR_ACCELEROMETER: + return INV_ICM20948_SENSOR_ACCELEROMETER; + case ANDROID_SENSOR_GYROSCOPE: + return INV_ICM20948_SENSOR_GYROSCOPE; + case ANDROID_SENSOR_RAW_ACCELEROMETER: + return INV_ICM20948_SENSOR_RAW_ACCELEROMETER; + case ANDROID_SENSOR_RAW_GYROSCOPE: + return INV_ICM20948_SENSOR_RAW_GYROSCOPE; + case ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED: + return INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED; + case ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED: + return INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED; + case ANDROID_SENSOR_ACTIVITY_CLASSIFICATON: + return INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON; + case ANDROID_SENSOR_STEP_DETECTOR: + return INV_ICM20948_SENSOR_STEP_DETECTOR; + case ANDROID_SENSOR_STEP_COUNTER: + return INV_ICM20948_SENSOR_STEP_COUNTER; + case ANDROID_SENSOR_GAME_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR; + case ANDROID_SENSOR_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_ROTATION_VECTOR; + case ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR: + return INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR; + case ANDROID_SENSOR_GEOMAGNETIC_FIELD: + return INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD; + case ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION: + return INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION; + case ANDROID_SENSOR_FLIP_PICKUP: + return INV_ICM20948_SENSOR_FLIP_PICKUP; + case ANDROID_SENSOR_WAKEUP_TILT_DETECTOR: + return INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR; + case ANDROID_SENSOR_GRAVITY: + return INV_ICM20948_SENSOR_GRAVITY; + case ANDROID_SENSOR_LINEAR_ACCELERATION: + return INV_ICM20948_SENSOR_LINEAR_ACCELERATION; + case ANDROID_SENSOR_ORIENTATION: + return INV_ICM20948_SENSOR_ORIENTATION; + case ANDROID_SENSOR_B2S: + return INV_ICM20948_SENSOR_B2S; + default: + return INV_ICM20948_SENSOR_MAX; + } +} + +ICM_20948_Status_e inv_icm20948_set_gyro_sf(ICM_20948_Device_t *pdev, unsigned char div, int gyro_level) +{ + ICM_20948_Status_e result = ICM_20948_Stat_Ok; + + if (pdev->_dmp_firmware_available == false) + return ICM_20948_Stat_DMPNotSupported; + + // gyro_level should be set to 4 regardless of fullscale, due to the addition of API dmp_icm20648_set_gyro_fsr() + gyro_level = 4; + + // First read the TIMEBASE_CORRECTION_PLL register from Bank 1 + int8_t pll; // Signed. Typical value is 0x18 + result = ICM_20948_set_bank(pdev, 1); + result = ICM_20948_execute_r(pdev, AGB1_REG_TIMEBASE_CORRECTION_PLL, (uint8_t *)&pll, 1); + if (result != ICM_20948_Stat_Ok) + { + return result; + } + + pdev->_gyroSFpll = pll; // Record the PLL value so we can debug print it + + // Now calculate the Gyro SF using code taken from the InvenSense example (inv_icm20948_set_gyro_sf) + + long gyro_sf; + + unsigned long long const MagicConstant = 264446880937391LL; + unsigned long long const MagicConstantScale = 100000LL; + unsigned long long ResultLL; + + if (pll & 0x80) + { + ResultLL = (MagicConstant * (long long)(1ULL << gyro_level) * (1 + div) / (1270 - (pll & 0x7F)) / MagicConstantScale); + } + else + { + ResultLL = (MagicConstant * (long long)(1ULL << gyro_level) * (1 + div) / (1270 + pll) / MagicConstantScale); + } + /* + In above deprecated FP version, worst case arguments can produce a result that overflows a signed long. + Here, for such cases, we emulate the FP behavior of setting the result to the maximum positive value, as + the compiler's conversion of a u64 to an s32 is simple truncation of the u64's high half, sadly.... + */ + if (ResultLL > 0x7FFFFFFF) + gyro_sf = 0x7FFFFFFF; + else + gyro_sf = (long)ResultLL; + + pdev->_gyroSF = gyro_sf; // Record value so we can debug print it + + // Finally, write the value to the DMP GYRO_SF register + unsigned char gyro_sf_reg[4]; + gyro_sf_reg[0] = (unsigned char)(gyro_sf >> 24); + gyro_sf_reg[1] = (unsigned char)(gyro_sf >> 16); + gyro_sf_reg[2] = (unsigned char)(gyro_sf >> 8); + gyro_sf_reg[3] = (unsigned char)(gyro_sf & 0xff); + result = inv_icm20948_write_mems(pdev, GYRO_SF, 4, (const unsigned char *)&gyro_sf_reg); + + return result; +} diff --git a/lib/ICM-20948/src/util/ICM_20948_C.h b/lib/ICM-20948/src/util/ICM_20948_C.h new file mode 100644 index 0000000..c732ebc --- /dev/null +++ b/lib/ICM-20948/src/util/ICM_20948_C.h @@ -0,0 +1,303 @@ +/* + +This is a C-compatible interface to the features presented by the ICM 20948 9-axis device +The imementation of the interface is flexible + +*/ + +#ifndef _ICM_20948_C_H_ +#define _ICM_20948_C_H_ + +#include +#include +#include + +#include "ICM_20948_REGISTERS.h" +#include "ICM_20948_ENUMERATIONS.h" // This is to give users access to usable value definiitons +#include "AK09916_ENUMERATIONS.h" +#include "ICM_20948_DMP.h" + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + +extern int memcmp(const void *, const void *, size_t); // Avoid compiler warnings + +// Define if the DMP will be supported +// Note: you must have 14290/14301 Bytes of program memory available to store the DMP firmware! +//#define ICM_20948_USE_DMP // Uncomment this line to enable DMP support. You can of course use ICM_20948_USE_DMP as a compiler flag too + +// There are two versions of the InvenSense DMP firmware for the ICM20948 - with slightly different sizes +#define DMP_CODE_SIZE 14301 /* eMD-SmartMotion-ICM20948-1.1.0-MP */ +//#define DMP_CODE_SIZE 14290 /* ICM20948_eMD_nucleo_1.0 */ + + +#define ICM_20948_I2C_ADDR_AD0 0x68 // Or 0x69 when AD0 is high +#define ICM_20948_I2C_ADDR_AD1 0x69 // +#define ICM_20948_WHOAMI 0xEA + +#define MAG_AK09916_I2C_ADDR 0x0C +#define MAG_AK09916_WHO_AM_I 0x4809 +#define MAG_REG_WHO_AM_I 0x00 + +/** @brief Max size that can be read across I2C or SPI data lines */ +#define INV_MAX_SERIAL_READ 16 +/** @brief Max size that can be written across I2C or SPI data lines */ +#define INV_MAX_SERIAL_WRITE 16 + + typedef enum + { + ICM_20948_Stat_Ok = 0x00, // The only return code that means all is well + ICM_20948_Stat_Err, // A general error + ICM_20948_Stat_NotImpl, // Returned by virtual functions that are not implemented + ICM_20948_Stat_ParamErr, + ICM_20948_Stat_WrongID, + ICM_20948_Stat_InvalSensor, // Tried to apply a function to a sensor that does not support it (e.g. DLPF to the temperature sensor) + ICM_20948_Stat_NoData, + ICM_20948_Stat_SensorNotSupported, + ICM_20948_Stat_DMPNotSupported, // DMP not supported (no #define ICM_20948_USE_DMP) + ICM_20948_Stat_DMPVerifyFail, // DMP was written but did not verify correctly + ICM_20948_Stat_FIFONoDataAvail, // FIFO contains no data + ICM_20948_Stat_FIFOIncompleteData, // FIFO contained incomplete data + ICM_20948_Stat_FIFOMoreDataAvail, // FIFO contains more data + ICM_20948_Stat_UnrecognisedDMPHeader, + ICM_20948_Stat_UnrecognisedDMPHeader2, + ICM_20948_Stat_InvalDMPRegister, // Invalid DMP Register + + ICM_20948_Stat_NUM, + ICM_20948_Stat_Unknown, + } ICM_20948_Status_e; + + typedef enum + { + ICM_20948_Internal_Acc = (1 << 0), + ICM_20948_Internal_Gyr = (1 << 1), + ICM_20948_Internal_Mag = (1 << 2), + ICM_20948_Internal_Tmp = (1 << 3), + ICM_20948_Internal_Mst = (1 << 4), // I2C Master Ineternal + } ICM_20948_InternalSensorID_bm; // A bitmask of internal sensor IDs + + typedef union + { + int16_t i16bit[3]; + uint8_t u8bit[6]; + } ICM_20948_axis3bit16_t; + + typedef union + { + int16_t i16bit; + uint8_t u8bit[2]; + } ICM_20948_axis1bit16_t; + + typedef struct + { + uint8_t a : 2; + uint8_t g : 2; + uint8_t reserved_0 : 4; + } ICM_20948_fss_t; // Holds full-scale settings to be able to extract measurements with units + + typedef struct + { + uint8_t a; + uint8_t g; + } ICM_20948_dlpcfg_t; // Holds digital low pass filter settings. Members are type ICM_20948_ACCEL_CONFIG_DLPCFG_e + + typedef struct + { + uint16_t a; + uint8_t g; + } ICM_20948_smplrt_t; + + typedef struct + { + uint8_t I2C_MST_INT_EN : 1; + uint8_t DMP_INT1_EN : 1; + uint8_t PLL_RDY_EN : 1; + uint8_t WOM_INT_EN : 1; + uint8_t REG_WOF_EN : 1; + uint8_t RAW_DATA_0_RDY_EN : 1; + uint8_t FIFO_OVERFLOW_EN_4 : 1; + uint8_t FIFO_OVERFLOW_EN_3 : 1; + uint8_t FIFO_OVERFLOW_EN_2 : 1; + uint8_t FIFO_OVERFLOW_EN_1 : 1; + uint8_t FIFO_OVERFLOW_EN_0 : 1; + uint8_t FIFO_WM_EN_4 : 1; + uint8_t FIFO_WM_EN_3 : 1; + uint8_t FIFO_WM_EN_2 : 1; + uint8_t FIFO_WM_EN_1 : 1; + uint8_t FIFO_WM_EN_0 : 1; + } ICM_20948_INT_enable_t; + + typedef union + { + ICM_20948_axis3bit16_t raw; + struct + { + int16_t x; + int16_t y; + int16_t z; + } axes; + } ICM_20948_axis3named_t; + + typedef struct + { + ICM_20948_axis3named_t acc; + ICM_20948_axis3named_t gyr; + ICM_20948_axis3named_t mag; + union + { + ICM_20948_axis1bit16_t raw; + int16_t val; + } tmp; + ICM_20948_fss_t fss; // Full-scale range settings for this measurement + uint8_t magStat1; + uint8_t magStat2; + } ICM_20948_AGMT_t; + + typedef struct + { + ICM_20948_Status_e (*write)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user); + ICM_20948_Status_e (*read)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user); + // void (*delay)(uint32_t ms); + void *user; + } ICM_20948_Serif_t; // This is the vtable of serial interface functions + extern const ICM_20948_Serif_t NullSerif; // Here is a default for initialization (NULL) + + typedef struct + { + const ICM_20948_Serif_t *_serif; // Pointer to the assigned Serif (Serial Interface) vtable + bool _dmp_firmware_available; // Indicates if the DMP firmware has been included. It + bool _firmware_loaded; // Indicates if DMP has been loaded + uint8_t _last_bank; // Keep track of which bank was selected last - to avoid unnecessary writes + uint8_t _last_mems_bank; // Keep track of which bank was selected last - to avoid unnecessary writes + int32_t _gyroSF; // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf + int8_t _gyroSFpll; + uint32_t _enabled_Android_0; // Keep track of which Android sensors are enabled: 0-31 + uint32_t _enabled_Android_1; // Keep track of which Android sensors are enabled: 32- + uint32_t _enabled_Android_intr_0; // Keep track of which Android sensor interrupts are enabled: 0-31 + uint32_t _enabled_Android_intr_1; // Keep track of which Android sensor interrupts are enabled: 32- + uint16_t _dataOutCtl1; // Diagnostics: record the setting of DATA_OUT_CTL1 + uint16_t _dataOutCtl2; // Diagnostics: record the setting of DATA_OUT_CTL2 + uint16_t _dataRdyStatus; // Diagnostics: record the setting of DATA_RDY_STATUS + uint16_t _motionEventCtl; // Diagnostics: record the setting of MOTION_EVENT_CTL + uint16_t _dataIntrCtl; // Diagnostics: record the setting of DATA_INTR_CTL + } ICM_20948_Device_t; // Definition of device struct type + + ICM_20948_Status_e ICM_20948_init_struct(ICM_20948_Device_t *pdev); // Initialize ICM_20948_Device_t + + // ICM_20948_Status_e ICM_20948_Startup( ICM_20948_Device_t* pdev ); // For the time being this performs a standardized startup routine + + ICM_20948_Status_e ICM_20948_link_serif(ICM_20948_Device_t *pdev, const ICM_20948_Serif_t *s); // Links a SERIF structure to the device + + // use the device's serif to perform a read or write + ICM_20948_Status_e ICM_20948_execute_r(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len); // Executes a R or W witht he serif vt as long as the pointers are not null + ICM_20948_Status_e ICM_20948_execute_w(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len); + + // Single-shot I2C on Master IF + ICM_20948_Status_e ICM_20948_i2c_controller_periph4_txn(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr); + ICM_20948_Status_e ICM_20948_i2c_master_single_w(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data); + ICM_20948_Status_e ICM_20948_i2c_master_single_r(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data); + + // Device Level + ICM_20948_Status_e ICM_20948_set_bank(ICM_20948_Device_t *pdev, uint8_t bank); // Sets the bank + ICM_20948_Status_e ICM_20948_sw_reset(ICM_20948_Device_t *pdev); // Performs a SW reset + ICM_20948_Status_e ICM_20948_sleep(ICM_20948_Device_t *pdev, bool on); // Set sleep mode for the chip + ICM_20948_Status_e ICM_20948_low_power(ICM_20948_Device_t *pdev, bool on); // Set low power mode for the chip + ICM_20948_Status_e ICM_20948_set_clock_source(ICM_20948_Device_t *pdev, ICM_20948_PWR_MGMT_1_CLKSEL_e source); // Choose clock source + ICM_20948_Status_e ICM_20948_get_who_am_i(ICM_20948_Device_t *pdev, uint8_t *whoami); // Return whoami in out prarmeter + ICM_20948_Status_e ICM_20948_check_id(ICM_20948_Device_t *pdev); // Return 'ICM_20948_Stat_Ok' if whoami matches ICM_20948_WHOAMI + ICM_20948_Status_e ICM_20948_data_ready(ICM_20948_Device_t *pdev); // Returns 'Ok' if data is ready + + // Interrupt Configuration + ICM_20948_Status_e ICM_20948_int_pin_cfg(ICM_20948_Device_t *pdev, ICM_20948_INT_PIN_CFG_t *write, ICM_20948_INT_PIN_CFG_t *read); // Set the INT pin configuration + ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_enable_t *write, ICM_20948_INT_enable_t *read); // Write and or read the interrupt enable information. If non-null the write operation occurs before the read, so as to verify that the write was successful + + // WoM Threshold Level Configuration + ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read); // Write and or read the Wake on Motion threshold. If non-null the write operation occurs before the read, so as to verify that the write was successful + + // Internal Sensor Options + ICM_20948_Status_e ICM_20948_set_sample_mode(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_LP_CONFIG_CYCLE_e mode); // Use to set accel, gyro, and I2C master into cycled or continuous modes + ICM_20948_Status_e ICM_20948_set_full_scale(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_fss_t fss); + ICM_20948_Status_e ICM_20948_set_dlpf_cfg(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_dlpcfg_t cfg); + ICM_20948_Status_e ICM_20948_enable_dlpf(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, bool enable); + ICM_20948_Status_e ICM_20948_set_sample_rate(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_smplrt_t smplrt); + + // Interface Things + ICM_20948_Status_e ICM_20948_i2c_master_passthrough(ICM_20948_Device_t *pdev, bool passthrough); + ICM_20948_Status_e ICM_20948_i2c_master_enable(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_i2c_master_reset(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_i2c_controller_configure_peripheral(ICM_20948_Device_t *pdev, uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut); + + // Higher Level + ICM_20948_Status_e ICM_20948_get_agmt(ICM_20948_Device_t *pdev, ICM_20948_AGMT_t *p); + + // FIFO + + ICM_20948_Status_e ICM_20948_enable_FIFO(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_reset_FIFO(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_set_FIFO_mode(ICM_20948_Device_t *pdev, bool snapshot); + ICM_20948_Status_e ICM_20948_get_FIFO_count(ICM_20948_Device_t *pdev, uint16_t *count); + ICM_20948_Status_e ICM_20948_read_FIFO(ICM_20948_Device_t *pdev, uint8_t *data, uint8_t len); + + // DMP + + ICM_20948_Status_e ICM_20948_enable_DMP(ICM_20948_Device_t *pdev, bool enable); + ICM_20948_Status_e ICM_20948_reset_DMP(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_firmware_load(ICM_20948_Device_t *pdev); + ICM_20948_Status_e ICM_20948_set_dmp_start_address(ICM_20948_Device_t *pdev, unsigned short address); + + /** @brief Loads the DMP firmware from SRAM + * @param[in] data pointer where the image + * @param[in] size size if the image + * @param[in] load_addr address to loading the image + * @return 0 in case of success, -1 for any error + */ + ICM_20948_Status_e inv_icm20948_firmware_load(ICM_20948_Device_t *pdev, const unsigned char *data, unsigned short size, unsigned short load_addr); + /** + * @brief Write data to a register in DMP memory + * @param[in] DMP memory address + * @param[in] number of byte to be written + * @param[out] output data from the register + * @return 0 if successful. + */ + ICM_20948_Status_e inv_icm20948_write_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, const unsigned char *data); + /** + * @brief Read data from a register in DMP memory + * @param[in] DMP memory address + * @param[in] number of byte to be read + * @param[in] input data from the register + * @return 0 if successful. + */ + ICM_20948_Status_e inv_icm20948_read_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, unsigned char *data); + + ICM_20948_Status_e inv_icm20948_set_dmp_sensor_period(ICM_20948_Device_t *pdev, enum DMP_ODR_Registers odr_reg, uint16_t interval); + ICM_20948_Status_e inv_icm20948_enable_dmp_sensor(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state); // State is actually boolean + ICM_20948_Status_e inv_icm20948_enable_dmp_sensor_int(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state); // State is actually boolean + static uint8_t sensor_type_2_android_sensor(enum inv_icm20948_sensor sensor); + enum inv_icm20948_sensor inv_icm20948_sensor_android_2_sensor_type(int sensor); + + ICM_20948_Status_e inv_icm20948_read_dmp_data(ICM_20948_Device_t *pdev, icm_20948_DMP_data_t *data); + ICM_20948_Status_e inv_icm20948_set_gyro_sf(ICM_20948_Device_t *pdev, unsigned char div, int gyro_level); + + // ToDo: + + /* + Want to access magnetometer throught the I2C master interface... + + // If using the I2C master to read from the magnetometer + // Enable the I2C master to talk to the magnetometer through the ICM 20948 + myICM.i2cMasterEnable( true ); + SERIAL_PORT.print(F("Enabling the I2C master returned ")); SERIAL_PORT.println(myICM.statusString()); + myICM.i2cControllerConfigurePeripheral ( 0, MAG_AK09916_I2C_ADDR, REG_ST1, 9, true, true, false, false, false ); + SERIAL_PORT.print(F("Configuring the magnetometer peripheral returned ")); SERIAL_PORT.println(myICM.statusString()); + + // Operate the I2C master in duty-cycled mode + myICM.setSampleMode( (ICM_20948_Internal_Mst | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled ); // options: ICM_20948_Sample_Mode_Continuous or ICM_20948_Sample_Mode_Cycled +*/ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_C_H_ */ diff --git a/lib/ICM-20948/src/util/ICM_20948_DMP.h b/lib/ICM-20948/src/util/ICM_20948_DMP.h new file mode 100644 index 0000000..2354016 --- /dev/null +++ b/lib/ICM-20948/src/util/ICM_20948_DMP.h @@ -0,0 +1,695 @@ +/* + +This file contains a useful c translation of the DMP register map + +*/ + +#ifndef _ICM_20948_DMP_H_ +#define _ICM_20948_DMP_H_ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + +#define DMP_START_ADDRESS ((unsigned short)0x1000) +#define DMP_MEM_BANK_SIZE 256 +#define DMP_LOAD_START 0x90 + +#define CFG_FIFO_SIZE (4222) + +// AGB0_REG_DMP_INT_STATUS bit definitions +#define BIT_WAKE_ON_MOTION_INT 0x08 +#define BIT_MSG_DMP_INT 0x0002 +#define BIT_MSG_DMP_INT_0 0x0100 // CI Command + +#define BIT_MSG_DMP_INT_2 0x0200 // CIM Command - SMD +#define BIT_MSG_DMP_INT_3 0x0400 // CIM Command - Pedometer + +#define BIT_MSG_DMP_INT_4 0x1000 // CIM Command - Pedometer binning +#define BIT_MSG_DMP_INT_5 0x2000 // CIM Command - Bring To See Gesture +#define BIT_MSG_DMP_INT_6 0x4000 // CIM Command - Look To See Gesture + +// Appendix I: DMP register addresses + +// data output control +#define DATA_OUT_CTL1 (4 * 16) // 16-bit: Data output control 1 register : configure DMP to output required data +#define DATA_OUT_CTL2 (4 * 16 + 2) // 16-bit: Data output control 2 register : configure the BM, accel/gyro/compass accuracy and gesture such as Pick-up +#define DATA_INTR_CTL (4 * 16 + 12) // 16-bit: Determines which sensors can generate interrupt according to bit map defined for DATA_OUT_CTL1 +#define FIFO_WATERMARK (31 * 16 + 14) // 16-bit: DMP will send FIFO interrupt if FIFO count > FIFO watermark. FIFO watermark is set to 80% of actual FIFO size by default + +// motion event control +#define MOTION_EVENT_CTL (4 * 16 + 14) // 16-bit: configure DMP for Android L and Invensense specific features + +// indicates to DMP which sensors are available +/* 1: gyro samples available + 2: accel samples available + 8: secondary compass samples available */ +#define DATA_RDY_STATUS (8 * 16 + 10) // 16-bit: indicates to DMP which sensors are available + +// batch mode +#define BM_BATCH_CNTR (27 * 16) // 32-bit: Batch counter +#define BM_BATCH_THLD (19 * 16 + 12) // 32-bit: Batch mode threshold +#define BM_BATCH_MASK (21 * 16 + 14) // 16-bit + +// sensor output data rate: all 16-bit +#define ODR_ACCEL (11 * 16 + 14) // ODR_ACCEL Register for accel ODR +#define ODR_GYRO (11 * 16 + 10) // ODR_GYRO Register for gyro ODR +#define ODR_CPASS (11 * 16 + 6) // ODR_CPASS Register for compass ODR +#define ODR_ALS (11 * 16 + 2) // ODR_ALS Register for ALS ODR +#define ODR_QUAT6 (10 * 16 + 12) // ODR_QUAT6 Register for 6-axis quaternion ODR +#define ODR_QUAT9 (10 * 16 + 8) // ODR_QUAT9 Register for 9-axis quaternion ODR +#define ODR_PQUAT6 (10 * 16 + 4) // ODR_PQUAT6 Register for 6-axis pedometer quaternion ODR +#define ODR_GEOMAG (10 * 16 + 0) // ODR_GEOMAG Register for Geomag rv ODR +#define ODR_PRESSURE (11 * 16 + 12) // ODR_PRESSURE Register for pressure ODR +#define ODR_GYRO_CALIBR (11 * 16 + 8) // ODR_GYRO_CALIBR Register for calibrated gyro ODR +#define ODR_CPASS_CALIBR (11 * 16 + 4) // ODR_CPASS_CALIBR Register for calibrated compass ODR + +// sensor output data rate counter: all 16-bit +#define ODR_CNTR_ACCEL (9 * 16 + 14) // ODR_CNTR_ACCEL Register for accel ODR counter +#define ODR_CNTR_GYRO (9 * 16 + 10) // ODR_CNTR_GYRO Register for gyro ODR counter +#define ODR_CNTR_CPASS (9 * 16 + 6) // ODR_CNTR_CPASS Register for compass ODR counter +#define ODR_CNTR_ALS (9 * 16 + 2) // ODR_CNTR_ALS Register for ALS ODR counter +#define ODR_CNTR_QUAT6 (8 * 16 + 12) // ODR_CNTR_QUAT6 Register for 6-axis quaternion ODR counter +#define ODR_CNTR_QUAT9 (8 * 16 + 8) // ODR_CNTR_QUAT9 Register for 9-axis quaternion ODR counter +#define ODR_CNTR_PQUAT6 (8 * 16 + 4) // ODR_CNTR_PQUAT6 Register for 6-axis pedometer quaternion ODR counter +#define ODR_CNTR_GEOMAG (8 * 16 + 0) // ODR_CNTR_GEOMAG Register for Geomag rv ODR counter +#define ODR_CNTR_PRESSURE (9 * 16 + 12) // ODR_CNTR_PRESSURE Register for pressure ODR counter +#define ODR_CNTR_GYRO_CALIBR (9 * 16 + 8) // ODR_CNTR_GYRO_CALIBR Register for calibrated gyro ODR counter +#define ODR_CNTR_CPASS_CALIBR (9 * 16 + 4) // ODR_CNTR_CPASS_CALIBR Register for calibrated compass ODR counter + +// mounting matrix: all 32-bit +#define CPASS_MTX_00 (23 * 16) // Compass mount matrix and scale +#define CPASS_MTX_01 (23 * 16 + 4) // Compass mount matrix and scale +#define CPASS_MTX_02 (23 * 16 + 8) // Compass mount matrix and scale +#define CPASS_MTX_10 (23 * 16 + 12) // Compass mount matrix and scale +#define CPASS_MTX_11 (24 * 16) // Compass mount matrix and scale +#define CPASS_MTX_12 (24 * 16 + 4) // Compass mount matrix and scale +#define CPASS_MTX_20 (24 * 16 + 8) // Compass mount matrix and scale +#define CPASS_MTX_21 (24 * 16 + 12) // Compass mount matrix and scale +#define CPASS_MTX_22 (25 * 16) // Compass mount matrix and scale + +// bias calibration: all 32-bit +// The biases are 32-bits in chip frame in hardware unit scaled by: +// 2^12 (FSR 4g) for accel, 2^15 for gyro, in uT scaled by 2^16 for compass. +#define GYRO_BIAS_X (139 * 16 + 4) +#define GYRO_BIAS_Y (139 * 16 + 8) +#define GYRO_BIAS_Z (139 * 16 + 12) +#define ACCEL_BIAS_X (110 * 16 + 4) +#define ACCEL_BIAS_Y (110 * 16 + 8) +#define ACCEL_BIAS_Z (110 * 16 + 12) +#define CPASS_BIAS_X (126 * 16 + 4) +#define CPASS_BIAS_Y (126 * 16 + 8) +#define CPASS_BIAS_Z (126 * 16 + 12) + +#define GYRO_ACCURACY (138 * 16 + 2) +#define GYRO_BIAS_SET (138 * 16 + 6) +#define GYRO_LAST_TEMPR (134 * 16) +#define GYRO_SLOPE_X (78 * 16 + 4) +#define GYRO_SLOPE_Y (78 * 16 + 8) +#define GYRO_SLOPE_Z (78 * 16 + 12) + +// parameters for accel calibration +#define ACCEL_ACCURACY (97 * 16) +#define ACCEL_CAL_RESET (77 * 16) +#define ACCEL_VARIANCE_THRESH (93 * 16) +#define ACCEL_CAL_RATE (94 * 16 + 4) // 16-bit: 0 (225Hz, 112Hz, 56Hz) +#define ACCEL_PRE_SENSOR_DATA (97 * 16 + 4) +#define ACCEL_COVARIANCE (101 * 16 + 8) +#define ACCEL_ALPHA_VAR (91 * 16) // 32-bit: 1026019965 (225Hz) 977872018 (112Hz) 882002213 (56Hz) +#define ACCEL_A_VAR (92 * 16) // 32-bit: 47721859 (225Hz) 95869806 (112Hz) 191739611 (56Hz) +#define ACCEL_CAL_INIT (94 * 16 + 2) +#define ACCEL_CAL_SCALE_COVQ_IN_RANGE (194 * 16) +#define ACCEL_CAL_SCALE_COVQ_OUT_RANGE (195 * 16) +#define ACCEL_CAL_TEMPERATURE_SENSITIVITY (194 * 16 + 4) +#define ACCEL_CAL_TEMPERATURE_OFFSET_TRIM (194 * 16 + 12) + +#define CPASS_ACCURACY (37 * 16) +#define CPASS_BIAS_SET (34 * 16 + 14) +#define MAR_MODE (37 * 16 + 2) +#define CPASS_COVARIANCE (115 * 16) +#define CPASS_COVARIANCE_CUR (118 * 16 + 8) +#define CPASS_REF_MAG_3D (122 * 16) +#define CPASS_CAL_INIT (114 * 16) +#define CPASS_EST_FIRST_BIAS (113 * 16) +#define MAG_DISTURB_STATE (113 * 16 + 2) +#define CPASS_VAR_COUNT (112 * 16 + 6) +#define CPASS_COUNT_7 (87 * 16 + 2) +#define CPASS_MAX_INNO (124 * 16) +#define CPASS_BIAS_OFFSET (113 * 16 + 4) +#define CPASS_CUR_BIAS_OFFSET (114 * 16 + 4) +#define CPASS_PRE_SENSOR_DATA (87 * 16 + 4) + +// Compass Cal params to be adjusted according to sampling rate +#define CPASS_TIME_BUFFER (112 * 16 + 14) +#define CPASS_RADIUS_3D_THRESH_ANOMALY (112 * 16 + 8) + +#define CPASS_STATUS_CHK (25 * 16 + 12) + +// gains +#define ACCEL_FB_GAIN (34 * 16) +#define ACCEL_ONLY_GAIN (16 * 16 + 12) // 32-bit: 15252014 (225Hz) 30504029 (112Hz) 61117001 (56Hz) +#define GYRO_SF (19 * 16) // 32-bit: gyro scaling factor + +// 9-axis +#define MAGN_THR_9X (80 * 16) +#define MAGN_LPF_THR_9X (80 * 16 + 8) +#define QFB_THR_9X (80 * 16 + 12) + +// DMP running counter +#define DMPRATE_CNTR (18 * 16 + 4) + +// pedometer +#define PEDSTD_BP_B (49 * 16 + 12) +#define PEDSTD_BP_A4 (52 * 16) +#define PEDSTD_BP_A3 (52 * 16 + 4) +#define PEDSTD_BP_A2 (52 * 16 + 8) +#define PEDSTD_BP_A1 (52 * 16 + 12) +#define PEDSTD_SB (50 * 16 + 8) +#define PEDSTD_SB_TIME (50 * 16 + 12) +#define PEDSTD_PEAKTHRSH (57 * 16 + 8) +#define PEDSTD_TIML (50 * 16 + 10) +#define PEDSTD_TIMH (50 * 16 + 14) +#define PEDSTD_PEAK (57 * 16 + 4) +#define PEDSTD_STEPCTR (54 * 16) +#define PEDSTD_STEPCTR2 (58 * 16 + 8) +#define PEDSTD_TIMECTR (60 * 16 + 4) +#define PEDSTD_DECI (58 * 16) +#define PEDSTD_SB2 (60 * 16 + 14) +#define STPDET_TIMESTAMP (18 * 16 + 8) +#define PEDSTEP_IND (19 * 16 + 4) +#define PED_Y_RATIO (17 * 16 + 0) + +// SMD +#define SMD_VAR_TH (141 * 16 + 12) +#define SMD_VAR_TH_DRIVE (143 * 16 + 12) +#define SMD_DRIVE_TIMER_TH (143 * 16 + 8) +#define SMD_TILT_ANGLE_TH (179 * 16 + 12) +#define BAC_SMD_ST_TH (179 * 16 + 8) +#define BAC_ST_ALPHA4 (180 * 16 + 12) +#define BAC_ST_ALPHA4A (176 * 16 + 12) + +// Wake on Motion +#define WOM_ENABLE (64 * 16 + 14) +#define WOM_STATUS (64 * 16 + 6) +#define WOM_THRESHOLD_DMP (64 * 16) // Renamed by PaulZC to avoid duplication with the Bank 2 Reg 0x13 +#define WOM_CNTR_TH (64 * 16 + 12) + +// Activity Recognition +#define BAC_RATE (48 * 16 + 10) +#define BAC_STATE (179 * 16 + 0) +#define BAC_STATE_PREV (179 * 16 + 4) +#define BAC_ACT_ON (182 * 16 + 0) +#define BAC_ACT_OFF (183 * 16 + 0) +#define BAC_STILL_S_F (177 * 16 + 0) +#define BAC_RUN_S_F (177 * 16 + 4) +#define BAC_DRIVE_S_F (178 * 16 + 0) +#define BAC_WALK_S_F (178 * 16 + 4) +#define BAC_SMD_S_F (178 * 16 + 8) +#define BAC_BIKE_S_F (178 * 16 + 12) +#define BAC_E1_SHORT (146 * 16 + 0) +#define BAC_E2_SHORT (146 * 16 + 4) +#define BAC_E3_SHORT (146 * 16 + 8) +#define BAC_VAR_RUN (148 * 16 + 12) +#define BAC_TILT_INIT (181 * 16 + 0) +#define BAC_MAG_ON (225 * 16 + 0) +#define BAC_PS_ON (74 * 16 + 0) +#define BAC_BIKE_PREFERENCE (173 * 16 + 8) +#define BAC_MAG_I2C_ADDR (229 * 16 + 8) +#define BAC_PS_I2C_ADDR (75 * 16 + 4) +#define BAC_DRIVE_CONFIDENCE (144 * 16 + 0) +#define BAC_WALK_CONFIDENCE (144 * 16 + 4) +#define BAC_SMD_CONFIDENCE (144 * 16 + 8) +#define BAC_BIKE_CONFIDENCE (144 * 16 + 12) +#define BAC_STILL_CONFIDENCE (145 * 16 + 0) +#define BAC_RUN_CONFIDENCE (145 * 16 + 4) +#define BAC_MODE_CNTR (150 * 16) +#define BAC_STATE_T_PREV (185 * 16 + 4) +#define BAC_ACT_T_ON (184 * 16 + 0) +#define BAC_ACT_T_OFF (184 * 16 + 4) +#define BAC_STATE_WRDBS_PREV (185 * 16 + 8) +#define BAC_ACT_WRDBS_ON (184 * 16 + 8) +#define BAC_ACT_WRDBS_OFF (184 * 16 + 12) +#define BAC_ACT_ON_OFF (190 * 16 + 2) +#define PREV_BAC_ACT_ON_OFF (188 * 16 + 2) +#define BAC_CNTR (48 * 16 + 2) + +// Flip/Pick-up +#define FP_VAR_ALPHA (245 * 16 + 8) +#define FP_STILL_TH (246 * 16 + 4) +#define FP_MID_STILL_TH (244 * 16 + 8) +#define FP_NOT_STILL_TH (246 * 16 + 8) +#define FP_VIB_REJ_TH (241 * 16 + 8) +#define FP_MAX_PICKUP_T_TH (244 * 16 + 12) +#define FP_PICKUP_TIMEOUT_TH (248 * 16 + 8) +#define FP_STILL_CONST_TH (246 * 16 + 12) +#define FP_MOTION_CONST_TH (240 * 16 + 8) +#define FP_VIB_COUNT_TH (242 * 16 + 8) +#define FP_STEADY_TILT_TH (247 * 16 + 8) +#define FP_STEADY_TILT_UP_TH (242 * 16 + 12) +#define FP_Z_FLAT_TH_MINUS (243 * 16 + 8) +#define FP_Z_FLAT_TH_PLUS (243 * 16 + 12) +#define FP_DEV_IN_POCKET_TH (76 * 16 + 12) +#define FP_PICKUP_CNTR (247 * 16 + 4) +#define FP_RATE (240 * 16 + 12) + +// Gyro FSR +#define GYRO_FULLSCALE (72 * 16 + 12) + +// Accel FSR +// The DMP scales accel raw data internally to align 1g as 2^25. +// To do this and output hardware unit again as configured FSR, write 0x4000000 to ACC_SCALE DMP register, and write 0x40000 to ACC_SCALE2 DMP register. +#define ACC_SCALE (30 * 16 + 0) // 32-bit: Write accel scaling value for internal use +#define ACC_SCALE2 (79 * 16 + 4) // 32-bit: Write accel scaling down value + +// EIS authentication +#define EIS_AUTH_INPUT (160 * 16 + 4) +#define EIS_AUTH_OUTPUT (160 * 16 + 0) + +// B2S +#define B2S_RATE (48 * 16 + 8) + +// B2S mounting matrix +#define B2S_MTX_00 (208 * 16) +#define B2S_MTX_01 (208 * 16 + 4) +#define B2S_MTX_02 (208 * 16 + 8) +#define B2S_MTX_10 (208 * 16 + 12) +#define B2S_MTX_11 (209 * 16) +#define B2S_MTX_12 (209 * 16 + 4) +#define B2S_MTX_20 (209 * 16 + 8) +#define B2S_MTX_21 (209 * 16 + 12) +#define B2S_MTX_22 (210 * 16) + +// Dmp3 orientation parameters (Q30) initialization +#define Q0_QUAT6 (33 * 16 + 0) +#define Q1_QUAT6 (33 * 16 + 4) +#define Q2_QUAT6 (33 * 16 + 8) +#define Q3_QUAT6 (33 * 16 + 12) + + enum DMP_ODR_Registers + { + DMP_ODR_Reg_Accel = ODR_ACCEL, // ODR_ACCEL Register for accel ODR + DMP_ODR_Reg_Gyro = ODR_GYRO, // ODR_GYRO Register for gyro ODR + DMP_ODR_Reg_Cpass = ODR_CPASS, // ODR_CPASS Register for compass ODR + DMP_ODR_Reg_ALS = ODR_ALS, // ODR_ALS Register for ALS ODR + DMP_ODR_Reg_Quat6 = ODR_QUAT6, // ODR_QUAT6 Register for 6-axis quaternion ODR + DMP_ODR_Reg_Quat9 = ODR_QUAT9, // ODR_QUAT9 Register for 9-axis quaternion ODR + DMP_ODR_Reg_PQuat6 = ODR_PQUAT6, // ODR_PQUAT6 Register for 6-axis pedometer quaternion ODR + DMP_ODR_Reg_Geomag = ODR_GEOMAG, // ODR_GEOMAG Register for Geomag RV ODR + DMP_ODR_Reg_Pressure = ODR_PRESSURE, // ODR_PRESSURE Register for pressure ODR + DMP_ODR_Reg_Gyro_Calibr = ODR_GYRO_CALIBR, // ODR_GYRO_CALIBR Register for calibrated gyro ODR + DMP_ODR_Reg_Cpass_Calibr = ODR_CPASS_CALIBR // ODR_CPASS_CALIBR Register for calibrated compass ODR + }; + + /** @brief Sensor identifier for control function + */ + enum inv_icm20948_sensor + { + INV_ICM20948_SENSOR_ACCELEROMETER = 0, + INV_ICM20948_SENSOR_GYROSCOPE, + INV_ICM20948_SENSOR_RAW_ACCELEROMETER, + INV_ICM20948_SENSOR_RAW_GYROSCOPE, + INV_ICM20948_SENSOR_MAGNETIC_FIELD_UNCALIBRATED, + INV_ICM20948_SENSOR_GYROSCOPE_UNCALIBRATED, + INV_ICM20948_SENSOR_ACTIVITY_CLASSIFICATON, + INV_ICM20948_SENSOR_STEP_DETECTOR, + INV_ICM20948_SENSOR_STEP_COUNTER, + INV_ICM20948_SENSOR_GAME_ROTATION_VECTOR, + INV_ICM20948_SENSOR_ROTATION_VECTOR, + INV_ICM20948_SENSOR_GEOMAGNETIC_ROTATION_VECTOR, + INV_ICM20948_SENSOR_GEOMAGNETIC_FIELD, + INV_ICM20948_SENSOR_WAKEUP_SIGNIFICANT_MOTION, + INV_ICM20948_SENSOR_FLIP_PICKUP, + INV_ICM20948_SENSOR_WAKEUP_TILT_DETECTOR, + INV_ICM20948_SENSOR_GRAVITY, + INV_ICM20948_SENSOR_LINEAR_ACCELERATION, + INV_ICM20948_SENSOR_ORIENTATION, + INV_ICM20948_SENSOR_B2S, + INV_ICM20948_SENSOR_RAW_MAGNETOMETER, + INV_ICM20948_SENSOR_MAX, + }; + + /* enum for android sensor*/ + enum ANDROID_SENSORS + { + ANDROID_SENSOR_META_DATA = 0, // 0 + ANDROID_SENSOR_ACCELEROMETER, // 1 + ANDROID_SENSOR_GEOMAGNETIC_FIELD, // 2 + ANDROID_SENSOR_ORIENTATION, // 3 + ANDROID_SENSOR_GYROSCOPE, // 4 + ANDROID_SENSOR_LIGHT, // 5 + ANDROID_SENSOR_PRESSURE, // 6 + ANDROID_SENSOR_TEMPERATURE, // 7 + ANDROID_SENSOR_WAKEUP_PROXIMITY, // 8 + ANDROID_SENSOR_GRAVITY, // 9 + ANDROID_SENSOR_LINEAR_ACCELERATION, // 10 + ANDROID_SENSOR_ROTATION_VECTOR, // 11 + ANDROID_SENSOR_HUMIDITY, // 12 + ANDROID_SENSOR_AMBIENT_TEMPERATURE, // 13 + ANDROID_SENSOR_MAGNETIC_FIELD_UNCALIBRATED, // 14 + ANDROID_SENSOR_GAME_ROTATION_VECTOR, // 15 + ANDROID_SENSOR_GYROSCOPE_UNCALIBRATED, // 16 + ANDROID_SENSOR_WAKEUP_SIGNIFICANT_MOTION, // 17 + ANDROID_SENSOR_STEP_DETECTOR, // 18 + ANDROID_SENSOR_STEP_COUNTER, // 19 + ANDROID_SENSOR_GEOMAGNETIC_ROTATION_VECTOR, // 20 + ANDROID_SENSOR_HEART_RATE, // 21 + ANDROID_SENSOR_PROXIMITY, // 22 + + ANDROID_SENSOR_WAKEUP_ACCELEROMETER, // 23 + ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD, // 24 + ANDROID_SENSOR_WAKEUP_ORIENTATION, // 25 + ANDROID_SENSOR_WAKEUP_GYROSCOPE, // 26 + ANDROID_SENSOR_WAKEUP_LIGHT, // 27 + ANDROID_SENSOR_WAKEUP_PRESSURE, // 28 + ANDROID_SENSOR_WAKEUP_GRAVITY, // 29 + ANDROID_SENSOR_WAKEUP_LINEAR_ACCELERATION, // 30 + ANDROID_SENSOR_WAKEUP_ROTATION_VECTOR, // 31 + ANDROID_SENSOR_WAKEUP_RELATIVE_HUMIDITY, // 32 + ANDROID_SENSOR_WAKEUP_AMBIENT_TEMPERATURE, // 33 + ANDROID_SENSOR_WAKEUP_MAGNETIC_FIELD_UNCALIBRATED, // 34 + ANDROID_SENSOR_WAKEUP_GAME_ROTATION_VECTOR, // 35 + ANDROID_SENSOR_WAKEUP_GYROSCOPE_UNCALIBRATED, // 36 + ANDROID_SENSOR_WAKEUP_STEP_DETECTOR, // 37 + ANDROID_SENSOR_WAKEUP_STEP_COUNTER, // 38 + ANDROID_SENSOR_WAKEUP_GEOMAGNETIC_ROTATION_VECTOR, // 39 + ANDROID_SENSOR_WAKEUP_HEART_RATE, // 40 + ANDROID_SENSOR_WAKEUP_TILT_DETECTOR, // 41 + ANDROID_SENSOR_RAW_ACCELEROMETER, // 42 + ANDROID_SENSOR_RAW_GYROSCOPE, // 43 + ANDROID_SENSOR_NUM_MAX, // 44 + + ANDROID_SENSOR_B2S, // 45 + ANDROID_SENSOR_FLIP_PICKUP, // 46 + ANDROID_SENSOR_ACTIVITY_CLASSIFICATON, // 47 + ANDROID_SENSOR_SCREEN_ROTATION, // 48 + SELF_TEST, // 49 + SETUP, // 50 + GENERAL_SENSORS_MAX // 51 + }; + +// Determines which base sensor needs to be on based upon ANDROID_SENSORS 0-31 +#define INV_NEEDS_ACCEL_MASK ((1L << 1) | (1L << 3) | (1L << 9) | (1L << 10) | (1L << 11) | (1L << 15) | (1L << 17) | (1L << 18) | (1L << 19) | (1L << 20) | (1L << 23) | (1L << 25) | (1L << 29) | (1L << 30) | (1L << 31)) +#define INV_NEEDS_GYRO_MASK ((1L << 3) | (1L << 4) | (1L << 9) | (1L << 10) | (1L << 11) | (1L << 15) | (1L << 16) | (1L << 25) | (1L << 26) | (1L << 29) | (1L << 30) | (1L << 31)) +#define INV_NEEDS_COMPASS_MASK ((1L << 2) | (1L << 3) | (1L << 11) | (1L << 14) | (1L << 20) | (1L << 24) | (1L << 25) | (1L << 31)) +#define INV_NEEDS_PRESSURE ((1L << 6) | (1L << 28)) + +// Determines which base sensor needs to be on based upon ANDROID_SENSORS 32- +#define INV_NEEDS_ACCEL_MASK1 ((1L << 3) | (1L << 5) | (1L << 6) | (1L << 7) | (1L << 9) | (1L << 10)) // I.e. 35, 37, 38, 39, 41, 42 +#define INV_NEEDS_GYRO_MASK1 ((1L << 3) | (1L << 4) | (1L << 11)) // I.e. 35, 36, 43 +#define INV_NEEDS_COMPASS_MASK1 ((1L << 2) | (1L << 7)) // I.e. 34 and 39 + + enum DMP_Data_Ready_Status_Register_Bits + { + DMP_Data_ready_Gyro = 0x0001, // Gyro samples available + DMP_Data_ready_Accel = 0x0002, // Accel samples available + DMP_Data_ready_Secondary_Compass = 0x0008 // Secondary compass samples available + }; + + enum DMP_Data_Output_Control_1_Register_Bits + { + DMP_Data_Output_Control_1_Step_Ind_0 = 0x0001, // Pedometer Step Indicator Bit 0 + DMP_Data_Output_Control_1_Step_Ind_1 = 0x0002, // Pedometer Step Indicator Bit 1 + DMP_Data_Output_Control_1_Step_Ind_2 = 0x0004, // Pedometer Step Indicator Bit 2 + DMP_Data_Output_Control_1_Header2 = 0x0008, // Header 2 + DMP_Data_Output_Control_1_Step_Detector = 0x0010, // Pedometer Step Detector + DMP_Data_Output_Control_1_Compass_Calibr = 0x0020, // 32-bit calibrated compass + DMP_Data_Output_Control_1_Gyro_Calibr = 0x0040, // 32-bit calibrated gyro + DMP_Data_Output_Control_1_Pressure = 0x0080, // 16-bit Pressure + DMP_Data_Output_Control_1_Geomag = 0x0100, // 32-bit Geomag rv + heading accuracy + DMP_Data_Output_Control_1_PQuat6 = 0x0200, // 16-bit pedometer quaternion + DMP_Data_Output_Control_1_Quat9 = 0x0400, // 32-bit 9-axis quaternion + heading accuracy + DMP_Data_Output_Control_1_Quat6 = 0x0800, // 32-bit 6-axis quaternion + DMP_Data_Output_Control_1_ALS = 0x1000, // 16-bit ALS + DMP_Data_Output_Control_1_Compass = 0x2000, // 16-bit compass + DMP_Data_Output_Control_1_Gyro = 0x4000, // 16-bit gyro + DMP_Data_Output_Control_1_Accel = 0x8000 // 16-bit accel + }; + + enum DMP_Data_Output_Control_2_Register_Bits + { + DMP_Data_Output_Control_2_Secondary_On_Off = 0x0040, + DMP_Data_Output_Control_2_Activity_Recognition_BAC = 0x0080, + DMP_Data_Output_Control_2_Batch_Mode_Enable = 0x0100, + DMP_Data_Output_Control_2_Pickup = 0x0400, + DMP_Data_Output_Control_2_Fsync_Detection = 0x0800, + DMP_Data_Output_Control_2_Compass_Accuracy = 0x1000, + DMP_Data_Output_Control_2_Gyro_Accuracy = 0x2000, + DMP_Data_Output_Control_2_Accel_Accuracy = 0x4000 + }; + + enum DMP_Motion_Event_Control_Register_Bits + { + DMP_Motion_Event_Control_Activity_Recog_Pedom_Accel = 0x0002, // Activity Recognition / Pedometer accel only + DMP_Motion_Event_Control_Bring_Look_To_See = 0x0004, + DMP_Motion_Event_Control_Geomag = 0x0008, // Geomag rv + DMP_Motion_Event_Control_Pickup = 0x0010, + DMP_Motion_Event_Control_BTS = 0x0020, + DMP_Motion_Event_Control_9axis = 0x0040, + DMP_Motion_Event_Control_Compass_Calibr = 0x0080, + DMP_Motion_Event_Control_Gyro_Calibr = 0x0100, + DMP_Motion_Event_Control_Accel_Calibr = 0x0200, + DMP_Motion_Event_Control_Significant_Motion_Det = 0x0800, + DMP_Motion_Event_Control_Tilt_Interrupt = 0x1000, + DMP_Motion_Event_Control_Pedometer_Interrupt = 0x2000, + DMP_Motion_Event_Control_Activity_Recog_Pedom = 0x4000, + DMP_Motion_Event_Control_BAC_Wearable = 0x8000 + }; + + enum DMP_Header_Bitmap + { + DMP_header_bitmap_Header2 = 0x0008, + DMP_header_bitmap_Step_Detector = 0x0010, + DMP_header_bitmap_Compass_Calibr = 0x0020, + DMP_header_bitmap_Gyro_Calibr = 0x0040, + DMP_header_bitmap_Pressure = 0x0080, + DMP_header_bitmap_Geomag = 0x0100, + DMP_header_bitmap_PQuat6 = 0x0200, + DMP_header_bitmap_Quat9 = 0x0400, + DMP_header_bitmap_Quat6 = 0x0800, + DMP_header_bitmap_ALS = 0x1000, + DMP_header_bitmap_Compass = 0x2000, + DMP_header_bitmap_Gyro = 0x4000, + DMP_header_bitmap_Accel = 0x8000 + }; + + enum DMP_Header2_Bitmap + { + DMP_header2_bitmap_Secondary_On_Off = 0x0040, + DMP_header2_bitmap_Activity_Recog = 0x0080, + DMP_header2_bitmap_Pickup = 0x0400, + DMP_header2_bitmap_Fsync = 0x0800, + DMP_header2_bitmap_Compass_Accuracy = 0x1000, + DMP_header2_bitmap_Gyro_Accuracy = 0x2000, + DMP_header2_bitmap_Accel_Accuracy = 0x4000 + }; + + typedef struct // DMP Activity Recognition data + { + uint8_t Drive : 1; + uint8_t Walk : 1; + uint8_t Run : 1; + uint8_t Bike : 1; + uint8_t Tilt : 1; + uint8_t Still : 1; + uint8_t reserved : 2; + } icm_20948_DMP_Activity_t; + + typedef struct // DMP Secondary On/Off data + { + uint16_t Gyro_Off : 1; + uint16_t Gyro_On : 1; + uint16_t Compass_Off : 1; + uint16_t Compass_On : 1; + uint16_t Proximity_Off : 1; + uint16_t Proximity_On : 1; + uint16_t reserved : 10; + } icm_20948_DMP_Secondary_On_Off_t; + +#define icm_20948_DMP_Header_Bytes 2 +#define icm_20948_DMP_Header2_Bytes 2 +#define icm_20948_DMP_Raw_Accel_Bytes 6 +#define icm_20948_DMP_Raw_Gyro_Bytes 6 +#define icm_20948_DMP_Gyro_Bias_Bytes 6 +#define icm_20948_DMP_Compass_Bytes 6 +#define icm_20948_DMP_ALS_Bytes 8 +#define icm_20948_DMP_Quat6_Bytes 12 +#define icm_20948_DMP_Quat9_Bytes 14 +// <-- lcm20948MPUFifoControl.c suggests icm_20948_DMP_Step_Detector_Bytes comes here <-- +#define icm_20948_DMP_PQuat6_Bytes 6 +#define icm_20948_DMP_Geomag_Bytes 14 +#define icm_20948_DMP_Pressure_Bytes 6 +#define icm_20948_DMP_Gyro_Calibr_Bytes 12 // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Gyro_Calibr_Bytes is not supported? +#define icm_20948_DMP_Compass_Calibr_Bytes 12 +#define icm_20948_DMP_Step_Detector_Bytes 4 // See note above +#define icm_20948_DMP_Accel_Accuracy_Bytes 2 +#define icm_20948_DMP_Gyro_Accuracy_Bytes 2 +#define icm_20948_DMP_Compass_Accuracy_Bytes 2 +#define icm_20948_DMP_Fsync_Detection_Bytes 2 // lcm20948MPUFifoControl.c suggests icm_20948_DMP_Fsync_Detection_Bytes is not supported? +#define icm_20948_DMP_Pickup_Bytes 2 +#define icm_20948_DMP_Activity_Recognition_Bytes 6 +#define icm_20948_DMP_Secondary_On_Off_Bytes 2 +#define icm_20948_DMP_Footer_Bytes 2 +#define icm_20948_DMP_Maximum_Bytes 14 // The most bytes we will attempt to read from the FIFO in one go + + typedef struct + { + uint16_t header; + uint16_t header2; + union + { + uint8_t Bytes[icm_20948_DMP_Raw_Accel_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + } Data; + } Raw_Accel; + union + { + uint8_t Bytes[icm_20948_DMP_Raw_Gyro_Bytes + icm_20948_DMP_Gyro_Bias_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + int16_t BiasX; + int16_t BiasY; + int16_t BiasZ; + } Data; + } Raw_Gyro; + union + { + uint8_t Bytes[icm_20948_DMP_Compass_Bytes]; + struct + { + int16_t X; + int16_t Y; + int16_t Z; + } Data; + } Compass; + uint8_t ALS[icm_20948_DMP_ALS_Bytes]; // Byte[0]: Dummy, Byte[2:1]: Ch0DATA, Byte[4:3]: Ch1DATA, Byte[6:5]: PDATA, Byte[7]: Dummy + // The 6-Axis and 9-axis Quaternion outputs each consist of 12 bytes of data. + // These 12 bytes in turn consists of three 4-byte elements. + // 9-axis quaternion data and Geomag rv is always followed by 2-bytes of heading accuracy, hence the size of Quat9 and Geomag data size in the FIFO is 14 bytes. + // Quaternion data for both cases is cumulative/integrated values. + // For a given quaternion Q, the ordering of its elements is {Q1, Q2, Q3}. + // Each element is represented using Big Endian byte order. + // Q0 value is computed from this equation: Q20 + Q21 + Q22 + Q23 = 1. + // In case of drift, the sum will not add to 1, therefore, quaternion data need to be corrected with right bias values. + // The quaternion data is scaled by 2^30. + union + { + uint8_t Bytes[icm_20948_DMP_Quat6_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + } Data; + } Quat6; + union + { + uint8_t Bytes[icm_20948_DMP_Quat9_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + int16_t Accuracy; + } Data; + } Quat9; + union + { + uint8_t Bytes[icm_20948_DMP_PQuat6_Bytes]; + struct + { + int16_t Q1; + int16_t Q2; + int16_t Q3; + } Data; + } PQuat6; + union + { + uint8_t Bytes[icm_20948_DMP_Geomag_Bytes]; + struct + { + int32_t Q1; + int32_t Q2; + int32_t Q3; + int16_t Accuracy; + } Data; + } Geomag; + uint8_t Pressure[6]; // Byte [2:0]: Pressure data, Byte [5:3]: Temperature data + union + { + uint8_t Bytes[icm_20948_DMP_Gyro_Calibr_Bytes]; + struct + { + int32_t X; + int32_t Y; + int32_t Z; + } Data; + } Gyro_Calibr; // Hardware unit scaled by 2^15 + union + { + uint8_t Bytes[icm_20948_DMP_Compass_Calibr_Bytes]; + struct + { + int32_t X; + int32_t Y; + int32_t Z; + } Data; + } Compass_Calibr; // The unit is uT scaled by 2^16 + uint32_t Pedometer_Timestamp; // Timestamp as DMP cycle + uint16_t Accel_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Gyro_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Compass_Accuracy; // The accuracy is expressed as 0~3. The lowest is 0 and 3 is the highest. + uint16_t Fsync_Delay_Time; // The data is delay time between Fsync event and the 1st ODR event after Fsync event. + uint16_t Pickup; // The value “2” indicates pick up is detected. + // Activity Recognition data + // The data include Start and End states, and timestamp as DMP cycle. + // Byte [0]: State-Start, Byte [1]: State-End, Byte [5:2]: timestamp. + // The states are expressed as below. + // Drive: 0x01 + // Walk: 0x02 + // Run: 0x04 + // Bike: 0x08 + // Tilt: 0x10 + // Still: 0x20 + union + { + uint8_t Bytes[icm_20948_DMP_Activity_Recognition_Bytes]; + struct + { + icm_20948_DMP_Activity_t State_Start; + icm_20948_DMP_Activity_t State_End; + uint32_t Timestamp; + } Data; + } Activity_Recognition; + // Secondary On/Off data + // BAC algorithm requires sensors on/off through FIFO data to detect activities effectively and save power. + // The driver is expected to control sensors accordingly. + // The data indicates which sensor and on or off as below. + // Gyro Off: 0x01 + // Gyro On: 0x02 + // Compass Off: 0x04 + // Compass On: 0x08 + // Proximity Off: 0x10 + // Proximity On: 0x20 + union + { + uint8_t Bytes[icm_20948_DMP_Secondary_On_Off_Bytes]; + icm_20948_DMP_Secondary_On_Off_t Sensors; + } Secondary_On_Off; + uint16_t Footer; // Gyro count? + } icm_20948_DMP_data_t; + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_REGISTERS_H_ */ diff --git a/lib/ICM-20948/src/util/ICM_20948_ENUMERATIONS.h b/lib/ICM-20948/src/util/ICM_20948_ENUMERATIONS.h new file mode 100644 index 0000000..18b2aca --- /dev/null +++ b/lib/ICM-20948/src/util/ICM_20948_ENUMERATIONS.h @@ -0,0 +1,263 @@ +/* + +This file contains a useful c translation of the datasheet register map values + +*/ + +#ifndef _ICM_20948_ENUMERATIONS_H_ +#define _ICM_20948_ENUMERATIONS_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + + // // Generalized + // REG_BANK_SEL = 0x7F, + + // // Gyroscope and Accelerometer + // // User Bank 0 + // AGB0_REG_WHO_AM_I = 0x00, + // // Break + // AGB0_REG_USER_CTRL = 0x03, + // // Break + // AGB0_REG_LP_CONFIG = 0x05, + + typedef enum + { + ICM_20948_Sample_Mode_Continuous = 0x00, + ICM_20948_Sample_Mode_Cycled, + } ICM_20948_LP_CONFIG_CYCLE_e; + + // AGB0_REG_PWR_MGMT_1, + + typedef enum + { + ICM_20948_Clock_Internal_20MHz = 0x00, + ICM_20948_Clock_Auto, + ICM_20948_Clock_TimingReset = 0x07 + } ICM_20948_PWR_MGMT_1_CLKSEL_e; + + // AGB0_REG_PWR_MGMT_2, + // // Break + // AGB0_REG_INT_PIN_CONFIG = 0x0F, + // AGB0_REG_INT_ENABLE, + // AGB0_REG_INT_ENABLE_1, + // AGB0_REG_INT_ENABLE_2, + // AGB0_REG_INT_ENABLE_3, + // // Break + // AGB0_REG_I2C_MST_STATUS = 0x17, + // // Break + // AGB0_REG_INT_STATUS = 0x19, + // AGB0_REG_INT_STATUS_1, + // AGB0_REG_INT_STATUS_2, + // AGB0_REG_INT_STATUS_3, + // // Break + // AGB0_REG_DELAY_TIMEH = 0x28, + // AGB0_REG_DELAY_TIMEL, + // // Break + // AGB0_REG_ACCEL_XOUT_H = 0x2D, + // AGB0_REG_ACCEL_XOUT_L, + // AGB0_REG_ACCEL_YOUT_H, + // AGB0_REG_ACCEL_YOUT_L, + // AGB0_REG_ACCEL_ZOUT_H, + // AGB0_REG_ACCEL_ZOUT_L, + // AGB0_REG_GYRO_XOUT_H, + // AGB0_REG_GYRO_XOUT_L, + // AGB0_REG_GYRO_YOUT_H, + // AGB0_REG_GYRO_YOUT_L, + // AGB0_REG_GYRO_ZOUT_H, + // AGB0_REG_GYRO_ZOUT_L, + // AGB0_REG_TEMP_OUT_H, + // AGB0_REG_TEMP_OUT_L, + // AGB0_REG_EXT_PERIPH_SENS_DATA_00, + // AGB0_REG_EXT_PERIPH_SENS_DATA_01, + // AGB0_REG_EXT_PERIPH_SENS_DATA_02, + // AGB0_REG_EXT_PERIPH_SENS_DATA_03, + // AGB0_REG_EXT_PERIPH_SENS_DATA_04, + // AGB0_REG_EXT_PERIPH_SENS_DATA_05, + // AGB0_REG_EXT_PERIPH_SENS_DATA_06, + // AGB0_REG_EXT_PERIPH_SENS_DATA_07, + // AGB0_REG_EXT_PERIPH_SENS_DATA_08, + // AGB0_REG_EXT_PERIPH_SENS_DATA_09, + // AGB0_REG_EXT_PERIPH_SENS_DATA_10, + // AGB0_REG_EXT_PERIPH_SENS_DATA_11, + // AGB0_REG_EXT_PERIPH_SENS_DATA_12, + // AGB0_REG_EXT_PERIPH_SENS_DATA_13, + // AGB0_REG_EXT_PERIPH_SENS_DATA_14, + // AGB0_REG_EXT_PERIPH_SENS_DATA_15, + // AGB0_REG_EXT_PERIPH_SENS_DATA_16, + // AGB0_REG_EXT_PERIPH_SENS_DATA_17, + // AGB0_REG_EXT_PERIPH_SENS_DATA_18, + // AGB0_REG_EXT_PERIPH_SENS_DATA_19, + // AGB0_REG_EXT_PERIPH_SENS_DATA_20, + // AGB0_REG_EXT_PERIPH_SENS_DATA_21, + // AGB0_REG_EXT_PERIPH_SENS_DATA_22, + // AGB0_REG_EXT_PERIPH_SENS_DATA_23, + // // Break + // AGB0_REG_FIFO_EN_1 = 0x66, + // AGB0_REG_FIFO_EN_2, + // AGB0_REG_FIFO_MODE, + // // Break + // AGB0_REG_FIFO_COUNT_H = 0x70, + // AGB0_REG_FIFO_COUNT_L, + // AGB0_REG_FIFO_R_W, + // // Break + // AGB0_REG_DATA_RDY_STATUS = 0x74, + // // Break + // AGB0_REG_FIFO_CFG = 0x76, + // // Break + // AGB0_REG_MEM_START_ADDR = 0x7C, // Hmm, Invensense thought they were sneaky not listing these locations on the datasheet... + // AGB0_REG_MEM_R_W = 0x7D, // These three locations seem to be able to access some memory within the device + // AGB0_REG_MEM_BANK_SEL = 0x7E, // And that location is also where the DMP image gets loaded + // AGB0_REG_REG_BANK_SEL = 0x7F, + + // // Bank 1 + // AGB1_REG_SELF_TEST_X_GYRO = 0x02, + // AGB1_REG_SELF_TEST_Y_GYRO, + // AGB1_REG_SELF_TEST_Z_GYRO, + // // Break + // AGB1_REG_SELF_TEST_X_ACCEL = 0x0E, + // AGB1_REG_SELF_TEST_Y_ACCEL, + // AGB1_REG_SELF_TEST_Z_ACCEL, + // // Break + // AGB1_REG_XA_OFFS_H = 0x14, + // AGB1_REG_XA_OFFS_L, + // // Break + // AGB1_REG_YA_OFFS_H = 0x17, + // AGB1_REG_YA_OFFS_L, + // // Break + // AGB1_REG_ZA_OFFS_H = 0x1A, + // AGB1_REG_ZA_OFFS_L, + // // Break + // AGB1_REG_TIMEBASE_CORRECTION_PLL = 0x28, + // // Break + // AGB1_REG_REG_BANK_SEL = 0x7F, + + // // Bank 2 + // AGB2_REG_GYRO_SMPLRT_DIV = 0x00, + + /* +Gyro sample rate divider. Divides the internal sample rate to generate the sample +rate that controls sensor data output rate, FIFO sample rate, and DMP sequence rate. +NOTE: This register is only effective when FCHOICE = 1’b1 (FCHOICE_B register bit is 1’b0), and +(0 < DLPF_CFG < 7). +ODR is computed as follows: +1.1 kHz/(1+GYRO_SMPLRT_DIV[7:0]) +*/ + + // AGB2_REG_GYRO_CONFIG_1, + + typedef enum + { // Full scale range options in degrees per second + dps250 = 0x00, + dps500, + dps1000, + dps2000, + } ICM_20948_GYRO_CONFIG_1_FS_SEL_e; + + typedef enum + { // Format is dAbwB_nXbwY - A is integer part of 3db BW, B is fraction. X is integer part of nyquist bandwidth, Y is fraction + gyr_d196bw6_n229bw8 = 0x00, + gyr_d151bw8_n187bw6, + gyr_d119bw5_n154bw3, + gyr_d51bw2_n73bw3, + gyr_d23bw9_n35bw9, + gyr_d11bw6_n17bw8, + gyr_d5bw7_n8bw9, + gyr_d361bw4_n376bw5, + } ICM_20948_GYRO_CONFIG_1_DLPCFG_e; + + // AGB2_REG_GYRO_CONFIG_2, + // AGB2_REG_XG_OFFS_USRH, + // AGB2_REG_XG_OFFS_USRL, + // AGB2_REG_YG_OFFS_USRH, + // AGB2_REG_YG_OFFS_USRL, + // AGB2_REG_ZG_OFFS_USRH, + // AGB2_REG_ZG_OFFS_USRL, + // AGB2_REG_ODR_ALIGN_EN, + // // Break + // AGB2_REG_ACCEL_SMPLRT_DIV_1 = 0x10, + // AGB2_REG_ACCEL_SMPLRT_DIV_2, + // AGB2_REG_ACCEL_INTEL_CTRL, + // AGB2_REG_ACCEL_WOM_THR, + // AGB2_REG_ACCEL_CONFIG, + + typedef enum + { + gpm2 = 0x00, + gpm4, + gpm8, + gpm16, + } ICM_20948_ACCEL_CONFIG_FS_SEL_e; + + typedef enum + { // Format is dAbwB_nXbwZ - A is integer part of 3db BW, B is fraction. X is integer part of nyquist bandwidth, Y is fraction + acc_d246bw_n265bw = 0x00, + acc_d246bw_n265bw_1, + acc_d111bw4_n136bw, + acc_d50bw4_n68bw8, + acc_d23bw9_n34bw4, + acc_d11bw5_n17bw, + acc_d5bw7_n8bw3, + acc_d473bw_n499bw, + } ICM_20948_ACCEL_CONFIG_DLPCFG_e; + + // AGB2_REG_ACCEL_CONFIG_2, + // // Break + // AGB2_REG_FSYNC_CONFIG = 0x52, + // AGB2_REG_TEMP_CONFIG, + // AGB2_REG_MOD_CTRL_USR, + // // Break + // AGB2_REG_REG_BANK_SEL = 0x7F, + + // // Bank 3 + // AGB3_REG_I2C_MST_ODR_CONFIG = 0x00, + // AGB3_REG_I2C_MST_CTRL, + // AGB3_REG_I2C_MST_DELAY_CTRL, + // AGB3_REG_I2C_PERIPH0_ADDR, + // AGB3_REG_I2C_PERIPH0_REG, + // AGB3_REG_I2C_PERIPH0_CTRL, + // AGB3_REG_I2C_PERIPH0_DO, + // AGB3_REG_I2C_PERIPH1_ADDR, + // AGB3_REG_I2C_PERIPH1_REG, + // AGB3_REG_I2C_PERIPH1_CTRL, + // AGB3_REG_I2C_PERIPH1_DO, + // AGB3_REG_I2C_PERIPH2_ADDR, + // AGB3_REG_I2C_PERIPH2_REG, + // AGB3_REG_I2C_PERIPH2_CTRL, + // AGB3_REG_I2C_PERIPH2_DO, + // AGB3_REG_I2C_PERIPH3_ADDR, + // AGB3_REG_I2C_PERIPH3_REG, + // AGB3_REG_I2C_PERIPH3_CTRL, + // AGB3_REG_I2C_PERIPH3_DO, + // AGB3_REG_I2C_PERIPH4_ADDR, + // AGB3_REG_I2C_PERIPH4_REG, + // AGB3_REG_I2C_PERIPH4_CTRL, + // AGB3_REG_I2C_PERIPH4_DO, + // AGB3_REG_I2C_PERIPH4_DI, + // // Break + // AGB3_REG_REG_BANK_SEL = 0x7F, + + // // Magnetometer + // M_REG_WIA2 = 0x01, + // // Break + // M_REG_ST1 = 0x10, + // M_REG_HXL, + // M_REG_HXH, + // M_REG_HYL, + // M_REG_HYH, + // M_REG_HZL, + // M_REG_HZH, + // M_REG_ST2, + // // Break + // M_REG_CNTL2 = 0x31, + // M_REG_CNTL3, + // M_REG_TS1, + // M_REG_TS2, + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_ENUMERATIONS_H_ */ diff --git a/lib/ICM-20948/src/util/ICM_20948_REGISTERS.h b/lib/ICM-20948/src/util/ICM_20948_REGISTERS.h new file mode 100644 index 0000000..fb0e21f --- /dev/null +++ b/lib/ICM-20948/src/util/ICM_20948_REGISTERS.h @@ -0,0 +1,810 @@ +/* + +This file contains a useful c translation of the datasheet register map + +*/ + +#ifndef _ICM_20948_REGISTERS_H_ +#define _ICM_20948_REGISTERS_H_ + +#include + +#ifdef __cplusplus +extern "C" +{ +#endif /* __cplusplus */ + + typedef enum + { + // Generalized + REG_BANK_SEL = 0x7F, + + // Gyroscope and Accelerometer + // User Bank 0 + AGB0_REG_WHO_AM_I = 0x00, + AGB0_REG_LPF, + // Break + AGB0_REG_USER_CTRL = 0x03, + // Break + AGB0_REG_LP_CONFIG = 0x05, + AGB0_REG_PWR_MGMT_1, + AGB0_REG_PWR_MGMT_2, + // Break + AGB0_REG_INT_PIN_CONFIG = 0x0F, + AGB0_REG_INT_ENABLE, + AGB0_REG_INT_ENABLE_1, + AGB0_REG_INT_ENABLE_2, + AGB0_REG_INT_ENABLE_3, + // Break + AGB0_REG_I2C_MST_STATUS = 0x17, + AGB0_REG_DMP_INT_STATUS, + AGB0_REG_INT_STATUS, + AGB0_REG_INT_STATUS_1, + AGB0_REG_INT_STATUS_2, + AGB0_REG_INT_STATUS_3, + // Break + AGB0_REG_SINGLE_FIFO_PRIORITY_SEL = 0x26, + // Break + AGB0_REG_DELAY_TIMEH = 0x28, + AGB0_REG_DELAY_TIMEL, + // Break + AGB0_REG_ACCEL_XOUT_H = 0x2D, + AGB0_REG_ACCEL_XOUT_L, + AGB0_REG_ACCEL_YOUT_H, + AGB0_REG_ACCEL_YOUT_L, + AGB0_REG_ACCEL_ZOUT_H, + AGB0_REG_ACCEL_ZOUT_L, + AGB0_REG_GYRO_XOUT_H, + AGB0_REG_GYRO_XOUT_L, + AGB0_REG_GYRO_YOUT_H, + AGB0_REG_GYRO_YOUT_L, + AGB0_REG_GYRO_ZOUT_H, + AGB0_REG_GYRO_ZOUT_L, + AGB0_REG_TEMP_OUT_H, + AGB0_REG_TEMP_OUT_L, + AGB0_REG_EXT_PERIPH_SENS_DATA_00, + AGB0_REG_EXT_PERIPH_SENS_DATA_01, + AGB0_REG_EXT_PERIPH_SENS_DATA_02, + AGB0_REG_EXT_PERIPH_SENS_DATA_03, + AGB0_REG_EXT_PERIPH_SENS_DATA_04, + AGB0_REG_EXT_PERIPH_SENS_DATA_05, + AGB0_REG_EXT_PERIPH_SENS_DATA_06, + AGB0_REG_EXT_PERIPH_SENS_DATA_07, + AGB0_REG_EXT_PERIPH_SENS_DATA_08, + AGB0_REG_EXT_PERIPH_SENS_DATA_09, + AGB0_REG_EXT_PERIPH_SENS_DATA_10, + AGB0_REG_EXT_PERIPH_SENS_DATA_11, + AGB0_REG_EXT_PERIPH_SENS_DATA_12, + AGB0_REG_EXT_PERIPH_SENS_DATA_13, + AGB0_REG_EXT_PERIPH_SENS_DATA_14, + AGB0_REG_EXT_PERIPH_SENS_DATA_15, + AGB0_REG_EXT_PERIPH_SENS_DATA_16, + AGB0_REG_EXT_PERIPH_SENS_DATA_17, + AGB0_REG_EXT_PERIPH_SENS_DATA_18, + AGB0_REG_EXT_PERIPH_SENS_DATA_19, + AGB0_REG_EXT_PERIPH_SENS_DATA_20, + AGB0_REG_EXT_PERIPH_SENS_DATA_21, + AGB0_REG_EXT_PERIPH_SENS_DATA_22, + AGB0_REG_EXT_PERIPH_SENS_DATA_23, + // Break + AGB0_REG_TEMP_CONFIG = 0x53, + // Break + AGB0_REG_FIFO_EN_1 = 0x66, + AGB0_REG_FIFO_EN_2, + AGB0_REG_FIFO_RST, + AGB0_REG_FIFO_MODE, + // Break + AGB0_REG_FIFO_COUNT_H = 0x70, + AGB0_REG_FIFO_COUNT_L, + AGB0_REG_FIFO_R_W, + // Break + AGB0_REG_DATA_RDY_STATUS = 0x74, + AGB0_REG_HW_FIX_DISABLE, + AGB0_REG_FIFO_CFG, + // Break + AGB0_REG_MEM_START_ADDR = 0x7C, // Hmm, Invensense thought they were sneaky not listing these locations on the datasheet... + AGB0_REG_MEM_R_W = 0x7D, // These three locations seem to be able to access some memory within the device + AGB0_REG_MEM_BANK_SEL = 0x7E, // And that location is also where the DMP image gets loaded + AGB0_REG_REG_BANK_SEL = 0x7F, + + // Bank 1 + AGB1_REG_SELF_TEST_X_GYRO = 0x02, + AGB1_REG_SELF_TEST_Y_GYRO, + AGB1_REG_SELF_TEST_Z_GYRO, + // Break + AGB1_REG_SELF_TEST_X_ACCEL = 0x0E, + AGB1_REG_SELF_TEST_Y_ACCEL, + AGB1_REG_SELF_TEST_Z_ACCEL, + // Break + AGB1_REG_XA_OFFS_H = 0x14, + AGB1_REG_XA_OFFS_L, + // Break + AGB1_REG_YA_OFFS_H = 0x17, + AGB1_REG_YA_OFFS_L, + // Break + AGB1_REG_ZA_OFFS_H = 0x1A, + AGB1_REG_ZA_OFFS_L, + // Break + AGB1_REG_TIMEBASE_CORRECTION_PLL = 0x28, + // Break + AGB1_REG_REG_BANK_SEL = 0x7F, + + // Bank 2 + AGB2_REG_GYRO_SMPLRT_DIV = 0x00, + AGB2_REG_GYRO_CONFIG_1, + AGB2_REG_GYRO_CONFIG_2, + AGB2_REG_XG_OFFS_USRH, + AGB2_REG_XG_OFFS_USRL, + AGB2_REG_YG_OFFS_USRH, + AGB2_REG_YG_OFFS_USRL, + AGB2_REG_ZG_OFFS_USRH, + AGB2_REG_ZG_OFFS_USRL, + AGB2_REG_ODR_ALIGN_EN, + // Break + AGB2_REG_ACCEL_SMPLRT_DIV_1 = 0x10, + AGB2_REG_ACCEL_SMPLRT_DIV_2, + AGB2_REG_ACCEL_INTEL_CTRL, + AGB2_REG_ACCEL_WOM_THR, + AGB2_REG_ACCEL_CONFIG, + AGB2_REG_ACCEL_CONFIG_2, + // Break + AGB2_REG_PRS_ODR_CONFIG = 0x20, + // Break + AGB2_REG_PRGM_START_ADDRH = 0x50, + AGB2_REG_PRGM_START_ADDRL, + AGB2_REG_FSYNC_CONFIG, + AGB2_REG_TEMP_CONFIG, + AGB2_REG_MOD_CTRL_USR, + // Break + AGB2_REG_REG_BANK_SEL = 0x7F, + + // Bank 3 + AGB3_REG_I2C_MST_ODR_CONFIG = 0x00, + AGB3_REG_I2C_MST_CTRL, + AGB3_REG_I2C_MST_DELAY_CTRL, + AGB3_REG_I2C_PERIPH0_ADDR, + AGB3_REG_I2C_PERIPH0_REG, + AGB3_REG_I2C_PERIPH0_CTRL, + AGB3_REG_I2C_PERIPH0_DO, + AGB3_REG_I2C_PERIPH1_ADDR, + AGB3_REG_I2C_PERIPH1_REG, + AGB3_REG_I2C_PERIPH1_CTRL, + AGB3_REG_I2C_PERIPH1_DO, + AGB3_REG_I2C_PERIPH2_ADDR, + AGB3_REG_I2C_PERIPH2_REG, + AGB3_REG_I2C_PERIPH2_CTRL, + AGB3_REG_I2C_PERIPH2_DO, + AGB3_REG_I2C_PERIPH3_ADDR, + AGB3_REG_I2C_PERIPH3_REG, + AGB3_REG_I2C_PERIPH3_CTRL, + AGB3_REG_I2C_PERIPH3_DO, + AGB3_REG_I2C_PERIPH4_ADDR, + AGB3_REG_I2C_PERIPH4_REG, + AGB3_REG_I2C_PERIPH4_CTRL, + AGB3_REG_I2C_PERIPH4_DO, + AGB3_REG_I2C_PERIPH4_DI, + // Break + AGB3_REG_REG_BANK_SEL = 0x7F, + + // Magnetometer + M_REG_WIA2 = 0x01, + // Break + M_REG_ST1 = 0x10, + M_REG_HXL, + M_REG_HXH, + M_REG_HYL, + M_REG_HYH, + M_REG_HZL, + M_REG_HZH, + M_REG_ST2, + // Break + M_REG_CNTL2 = 0x31, + M_REG_CNTL3, + M_REG_TS1, + M_REG_TS2, + } ICM_20948_Reg_Addr_e; // These enums are not needed for the user, so they stay in this scope (simplifies naming among other things) + + // Type definitions for the registers + typedef struct + { + uint8_t WHO_AM_I; + } ICM_20948_WHO_AM_I_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t I2C_MST_RST : 1; + uint8_t SRAM_RST : 1; + uint8_t DMP_RST : 1; + uint8_t I2C_IF_DIS : 1; + uint8_t I2C_MST_EN : 1; + uint8_t FIFO_EN : 1; + uint8_t DMP_EN : 1; + } ICM_20948_USER_CTRL_t; + + typedef struct + { + uint8_t reserved_0 : 4; + uint8_t GYRO_CYCLE : 1; + uint8_t ACCEL_CYCLE : 1; + uint8_t I2C_MST_CYCLE : 1; + uint8_t reserved_1 : 1; + } ICM_20948_LP_CONFIG_t; + + typedef struct + { + uint8_t CLKSEL : 3; + uint8_t TEMP_DIS : 1; + uint8_t reserved_0 : 1; + uint8_t LP_EN : 1; + uint8_t SLEEP : 1; + uint8_t DEVICE_RESET : 1; + } ICM_20948_PWR_MGMT_1_t; + + typedef struct + { + uint8_t DISABLE_GYRO : 3; + uint8_t DIABLE_ACCEL : 3; + uint8_t reserved_0 : 2; + } ICM_20948_PWR_MGMT_2_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t BYPASS_EN : 1; + uint8_t FSYNC_INT_MODE_EN : 1; + uint8_t ACTL_FSYNC : 1; + uint8_t INT_ANYRD_2CLEAR : 1; + uint8_t INT1_LATCH_EN : 1; + uint8_t INT1_OPEN : 1; + uint8_t INT1_ACTL : 1; + } ICM_20948_INT_PIN_CFG_t; + + typedef struct + { + uint8_t I2C_MST_INT_EN : 1; + uint8_t DMP_INT1_EN : 1; + uint8_t PLL_READY_EN : 1; + uint8_t WOM_INT_EN : 1; + uint8_t reserved_0 : 3; + uint8_t REG_WOF_EN : 1; + } ICM_20948_INT_ENABLE_t; + + typedef struct + { + uint8_t RAW_DATA_0_RDY_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_INT_ENABLE_1_t; + + typedef union + { + struct + { + uint8_t FIFO_OVERFLOW_EN_40 : 5; + uint8_t reserved_0 : 3; + } grouped; + struct + { + uint8_t FIFO_OVERFLOW_EN_0 : 1; + uint8_t FIFO_OVERFLOW_EN_1 : 1; + uint8_t FIFO_OVERFLOW_EN_2 : 1; + uint8_t FIFO_OVERFLOW_EN_3 : 1; + uint8_t FIFO_OVERFLOW_EN_4 : 1; + uint8_t reserved_0 : 3; + } individual; + } ICM_20948_INT_ENABLE_2_t; + + // typedef struct{ + // uint8_t FIFO_OVERFLOW_EN_40 : 5; + // uint8_t reserved_0 : 3; + // }ICM_20948_INT_ENABLE_2_t; + + typedef union + { + struct + { + uint8_t FIFO_WM_EN_40 : 5; + uint8_t reserved_0 : 3; + } grouped; + struct + { + uint8_t FIFO_WM_EN_0 : 1; + uint8_t FIFO_WM_EN_1 : 1; + uint8_t FIFO_WM_EN_2 : 1; + uint8_t FIFO_WM_EN_3 : 1; + uint8_t FIFO_WM_EN_4 : 1; + uint8_t reserved_0 : 3; + } individual; + } ICM_20948_INT_ENABLE_3_t; + + // typedef struct{ + // uint8_t FIFO_WM_EN_40 : 5; + // uint8_t reserved_0 : 3; + // }ICM_20948_INT_ENABLE_3_t; + + typedef struct + { + uint8_t I2C_PERIPH0_NACK : 1; + uint8_t I2C_PERIPH1_NACK : 1; + uint8_t I2C_PERIPH2_NACK : 1; + uint8_t I2C_PERIPH3_NACK : 1; + uint8_t I2C_PERIPH4_NACK : 1; + uint8_t I2C_LOST_ARB : 1; + uint8_t I2C_PERIPH4_DONE : 1; + uint8_t PASS_THROUGH : 1; + } ICM_20948_I2C_MST_STATUS_t; + + typedef struct + { + uint8_t reserved0 : 1; + uint8_t DMP_INT_Motion_Detect_SMD : 1; + uint8_t reserved1 : 1; + uint8_t DMP_INT_Tilt_Event : 1; + uint8_t reserved2 : 4; + } ICM_20948_DMP_INT_STATUS_t; // Mostly guesswork from InvenSense App Note + + typedef struct + { + uint8_t I2C_MST_INT : 1; + uint8_t DMP_INT1 : 1; + uint8_t PLL_RDY_INT : 1; + uint8_t WOM_INT : 1; + uint8_t reserved_0 : 4; + } ICM_20948_INT_STATUS_t; + + typedef struct + { + uint8_t RAW_DATA_0_RDY_INT : 1; + uint8_t reserved_0 : 7; + } ICM_20948_INT_STATUS_1_t; + + // typedef union{ + // struct{ + // uint8_t FIFO_OVERFLOW_INT_40 : 5; + // uint8_t reserved_0 : 3; + // }grouped; + // struct{ + // uint8_t FIFO_OVERFLOW_INT_0 : 1; + // uint8_t FIFO_OVERFLOW_INT_1 : 1; + // uint8_t FIFO_OVERFLOW_INT_2 : 1; + // uint8_t FIFO_OVERFLOW_INT_3 : 1; + // uint8_t FIFO_OVERFLOW_INT_4 : 1; + // uint8_t reserved_0 : 3; + // }individual; + // }ICM_20948_INT_STATUS_2_t; + + typedef struct + { + uint8_t FIFO_OVERFLOW_INT_40 : 5; + uint8_t reserved_0 : 3; + } ICM_20948_INT_STATUS_2_t; + + // typedef union{ + // struct{ + // uint8_t FIFO_WM_INT_40 : 5; + // uint8_t reserved_0 : 3; + // }grouped; + // struct{ + // uint8_t FIFO_WM_INT_0 : 1; + // uint8_t FIFO_WM_INT_1 : 1; + // uint8_t FIFO_WM_INT_2 : 1; + // uint8_t FIFO_WM_INT_3 : 1; + // uint8_t FIFO_WM_INT_4 : 1; + // uint8_t reserved_0 : 3; + // }individual; + // }ICM_20948_INT_STATUS_3_t; + + typedef struct + { + uint8_t FIFO_WM_INT40 : 5; + uint8_t reserved_0 : 3; + } ICM_20948_INT_STATUS_3_t; + + typedef struct + { + uint8_t DELAY_TIMEH; + } ICM_20948_DELAY_TIMEH_t; + + typedef struct + { + uint8_t DELAY_TIMEL; + } ICM_20948_DELAY_TIMEL_t; + + typedef struct + { + uint8_t ACCEL_XOUT_H; + } ICM_20948_ACCEL_XOUT_H_t; + + typedef struct + { + uint8_t ACCEL_XOUT_L; + } ICM_20948_ACCEL_XOUT_L_t; + + typedef struct + { + uint8_t ACCEL_YOUT_H; + } ICM_20948_ACCEL_YOUT_H_t; + + typedef struct + { + uint8_t ACCEL_YOUT_L; + } ICM_20948_ACCEL_YOUT_L_t; + + typedef struct + { + uint8_t ACCEL_ZOUT_H; + } ICM_20948_ACCEL_ZOUT_H_t; + + typedef struct + { + uint8_t ACCEL_ZOUT_L; + } ICM_20948_ACCEL_ZOUT_L_t; + + typedef struct + { + uint8_t GYRO_XOUT_H; + } ICM_20948_GYRO_XOUT_H_t; + + typedef struct + { + uint8_t GYRO_XOUT_L; + } ICM_20948_GYRO_XOUT_L_t; + + typedef struct + { + uint8_t GYRO_YOUT_H; + } ICM_20948_GYRO_YOUT_H_t; + + typedef struct + { + uint8_t GYRO_YOUT_L; + } ICM_20948_GYRO_YOUT_L_t; + + typedef struct + { + uint8_t GYRO_ZOUT_H; + } ICM_20948_GYRO_ZOUT_H_t; + + typedef struct + { + uint8_t GYRO_ZOUT_L; + } ICM_20948_GYRO_ZOUT_L_t; + + typedef struct + { + uint8_t TEMP_OUT_H; + } ICM_20948_TEMP_OUT_H_t; + + typedef struct + { + uint8_t TEMP_OUT_L; + } ICM_20948_TEMP_OUT_L_t; + + typedef struct + { + uint8_t DATA; // Note: this is not worth copying 24 times, despite there being 24 registers like this one + } ICM_20948_EXT_PERIPH_SENS_DATA_t; + + typedef struct + { + uint8_t PERIPH_0_FIFO_EN : 1; + uint8_t PERIPH_1_FIFO_EN : 1; + uint8_t PERIPH_2_FIFO_EN : 1; + uint8_t PERIPH_3_FIFO_EN : 1; + uint8_t reserved_0 : 4; + } ICM_20948_FIFO_EN_1_t; + + typedef struct + { + uint8_t TEMP_FIFO_EN : 1; + uint8_t GYRO_X_FIFO_EN : 1; + uint8_t GYRO_Y_FIFO_EN : 1; + uint8_t GYRO_Z_FIFO_EN : 1; + uint8_t ACCEL_FIFO_EN : 1; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_EN_2_t; + + typedef struct + { + uint8_t FIFO_RESET : 5; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_RST_t; + + typedef struct + { + uint8_t FIFO_MODE : 5; + uint8_t reserved_0 : 3; + } ICM_20948_FIFO_MODE_t; + + typedef struct + { + uint8_t FIFO_COUNTH; + } ICM_20948_FIFO_COUNTH_t; + + typedef struct + { + uint8_t FIFO_COUNTL; + } ICM_20948_FIFO_COUNTL_t; + + typedef struct + { + uint8_t RAW_DATA_RDY : 4; + uint8_t reserved_0 : 3; + uint8_t WOF_STATUS : 1; + } ICM_20948_DATA_RDY_STATUS_t; + + typedef struct + { + uint8_t FIFO_CFG : 1; + uint8_t reserved_0 : 7; + } ICM_20948_FIFO_CFG_t; + + // User bank 1 Types + + typedef struct + { + uint8_t XG_ST_DATA; + } ICM_20948_SELF_TEST_X_GYRO_t; + + typedef struct + { + uint8_t YG_ST_DATA; + } ICM_20948_SELF_TEST_Y_GYRO_t; + + typedef struct + { + uint8_t ZG_ST_DATA; + } ICM_20948_SELF_TEST_Z_GYRO_t; + + typedef struct + { + uint8_t XA_ST_DATA; + } ICM_20948_SELF_TEST_X_ACCEL_t; + + typedef struct + { + uint8_t YA_ST_DATA; + } ICM_20948_SELF_TEST_Y_ACCEL_t; + + typedef struct + { + uint8_t ZA_ST_DATA; + } ICM_20948_SELF_TEST_Z_ACCEL_t; + + typedef struct + { + uint8_t XA_OFFS_14_7; + } ICM_20948_XA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t XA_OFFS_6_0 : 7; + } ICM_20948_XA_OFFS_L_t; + + typedef struct + { + uint8_t YA_OFFS_14_7; + } ICM_20948_YA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t YA_OFFS_6_0 : 7; + } ICM_20948_YA_OFFS_L_t; + + typedef struct + { + uint8_t ZA_OFFS_14_7; + } ICM_20948_ZA_OFFS_H_t; + + typedef struct + { + uint8_t reserved_0 : 1; + uint8_t ZA_OFFS_6_0 : 7; + } ICM_20948_ZA_OFFS_L_t; + + typedef struct + { + uint8_t TBC_PLL; + } ICM_20948_TIMEBASE_CORRECTION_PLL_t; + + // User Bank 2 Types + typedef struct + { + uint8_t GYRO_SMPLRT_DIV; + } ICM_20948_GYRO_SMPLRT_DIV_t; + + typedef struct + { + uint8_t GYRO_FCHOICE : 1; + uint8_t GYRO_FS_SEL : 2; + uint8_t GYRO_DLPFCFG : 3; + uint8_t reserved_0 : 2; + } ICM_20948_GYRO_CONFIG_1_t; + + typedef struct + { + uint8_t GYRO_AVGCFG : 3; + uint8_t ZGYRO_CTEN : 1; + uint8_t YGYRO_CTEN : 1; + uint8_t XGYRO_CTEN : 1; + uint8_t reserved_0 : 2; + } ICM_20948_GYRO_CONFIG_2_t; + + typedef struct + { + uint8_t XG_OFFS_USER_H; + } ICM_20948_XG_OFFS_USRH_t; + + typedef struct + { + uint8_t XG_OFFS_USER_L; + } ICM_20948_XG_OFFS_USRL_t; + + typedef struct + { + uint8_t YG_OFFS_USER_H; + } ICM_20948_YG_OFFS_USRH_t; + + typedef struct + { + uint8_t YG_OFFS_USER_L; + } ICM_20948_YG_OFFS_USRL_t; + + typedef struct + { + uint8_t ZG_OFFS_USER_H; + } ICM_20948_ZG_OFFS_USRH_t; + + typedef struct + { + uint8_t ZG_OFFS_USER_L; + } ICM_20948_ZG_OFFS_USRL_t; + + typedef struct + { + uint8_t ODR_ALIGN_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_ODR_ALIGN_EN_t; + + typedef struct + { + uint8_t ACCEL_SMPLRT_DIV_11_8 : 4; + uint8_t reserved_0 : 4; + } ICM_20948_ACCEL_SMPLRT_DIV_1_t; + + typedef struct + { + uint8_t ACCEL_SMPLRT_DIV_7_0; + } ICM_20948_ACCEL_SMPLRT_DIV_2_t; + + typedef struct + { + uint8_t ACCEL_INTEL_MODE_INT : 1; + uint8_t ACCEL_INTEL_EN : 1; + uint8_t reserved_0 : 6; + } ICM_20948_ACCEL_INTEL_CTRL_t; + + typedef struct + { + uint8_t WOM_THRESHOLD; + } ICM_20948_ACCEL_WOM_THR_t; + + typedef struct + { + uint8_t ACCEL_FCHOICE : 1; + uint8_t ACCEL_FS_SEL : 2; + uint8_t ACCEL_DLPFCFG : 3; + uint8_t reserved_0 : 2; + } ICM_20948_ACCEL_CONFIG_t; + + typedef struct + { + uint8_t DEC3_CFG : 2; + uint8_t AZ_ST_EN : 1; + uint8_t AY_ST_EN : 1; + uint8_t AX_ST_EN : 1; + uint8_t reserved_0 : 3; + } ICM_20948_ACCEL_CONFIG_2_t; + + typedef struct + { + uint8_t EXT_SYNC_SET : 4; + uint8_t WOF_EDGE_INT : 1; + uint8_t WOF_DEGLITCH_EN : 1; + uint8_t reserved_0 : 1; + uint8_t DELAY_TIME_EN : 1; + } ICM_20948_FSYNC_CONFIG_t; + + typedef struct + { + uint8_t TEMP_DLPFCFG : 3; + uint8_t reserved_0 : 5; + } ICM_20948_TEMP_CONFIG_t; + + typedef struct + { + uint8_t REG_LP_DMP_EN : 1; + uint8_t reserved_0 : 7; + } ICM_20948_MOD_CTRL_USR_t; + + // Bank 3 Types + + typedef struct + { + uint8_t I2C_MST_ODR_CONFIG : 4; + uint8_t reserved_0 : 4; + } ICM_20948_I2C_MST_ODR_CONFIG_t; + + typedef struct + { + uint8_t I2C_MST_CLK : 4; + uint8_t I2C_MST_P_NSR : 1; + uint8_t reserved_0 : 2; + uint8_t MULT_MST_EN : 1; + } ICM_20948_I2C_MST_CTRL_t; + + typedef struct + { + uint8_t I2C_PERIPH0_DELAY_EN : 1; + uint8_t I2C_PERIPH1_DELAY_EN : 1; + uint8_t I2C_PERIPH2_DELAY_EN : 1; + uint8_t I2C_PERIPH3_DELAY_EN : 1; + uint8_t I2C_PERIPH4_DELAY_EN : 1; + uint8_t reserved_0 : 2; + uint8_t DELAY_ES_SHADOW : 1; + } ICM_20948_I2C_MST_DELAY_CTRL_t; + + typedef struct + { + uint8_t ID : 7; + uint8_t RNW : 1; + } ICM_20948_I2C_PERIPHX_ADDR_t; + + typedef struct + { + uint8_t REG; + } ICM_20948_I2C_PERIPHX_REG_t; + + typedef struct + { + uint8_t LENG : 4; + uint8_t GRP : 1; + uint8_t REG_DIS : 1; + uint8_t BYTE_SW : 1; + uint8_t EN : 1; + } ICM_20948_I2C_PERIPHX_CTRL_t; + + typedef struct + { + uint8_t DO; + } ICM_20948_I2C_PERIPHX_DO_t; + + typedef struct + { + uint8_t DLY : 5; + uint8_t REG_DIS : 1; + uint8_t INT_EN : 1; + uint8_t EN : 1; + } ICM_20948_I2C_PERIPH4_CTRL_t; + + typedef struct + { + uint8_t DI; + } ICM_20948_I2C_PERIPH4_DI_t; + + // Bank select register! + + typedef struct + { + uint8_t reserved_0 : 4; + uint8_t USER_BANK : 2; + uint8_t reserved_1 : 2; + } ICM_20948_REG_BANK_SEL_t; + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* _ICM_20948_REGISTERS_H_ */ diff --git a/lib/ICM-20948/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 b/lib/ICM-20948/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 new file mode 100644 index 0000000..834203e --- /dev/null +++ b/lib/ICM-20948/src/util/eMD-SmartMotion-ICM20948-1.1.0-MP/icm20948_img.dmp3a.h_14301 @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x09, 0xed, 0xd1, 0xe8, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xf1, 0xa3, 0x8d, 0x93, + 0x20, 0xfd, 0x3f, 0x88, 0x6e, 0x76, 0x7e, 0x8d, 0x93, 0xbe, 0xa2, 0x20, 0xfd, 0x31, 0xa0, 0x2c, + 0xfd, 0x32, 0x34, 0xfd, 0x32, 0x3c, 0xfd, 0x32, 0xbe, 0xb9, 0xac, 0x8d, 0x20, 0xb8, 0xbe, 0xbe, + 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, 0x82, 0x93, 0x01, 0xa9, 0x83, + 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, 0x2c, 0x54, 0x7c, 0xbc, 0xbc, + 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, 0xfd, 0x37, 0x4c, 0xfd, 0x37, + 0x6c, 0xfd, 0x37, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, 0xbd, 0xbd, 0xb1, 0xb6, 0xba, + /* bank # 17 */ + 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, 0x2a, 0xf0, 0x50, 0x78, 0x87, + 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, 0xdf, 0xdf, 0xb0, 0x80, 0xf2, + 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, 0x1e, 0xb2, 0x86, 0xbe, 0xa0, + 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb6, 0x94, + 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, 0xbc, 0xb2, 0x8e, 0x94, 0xb8, + 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, + 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, 0xf5, 0x34, 0x54, 0x74, 0xbc, + 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xdf, 0xd8, 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, + 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, 0x90, 0xfc, 0x51, 0x00, 0x10, + 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, + 0x11, 0xdf, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, 0xda, 0xf8, 0xf4, 0x11, 0xdf, + 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, 0xf4, 0x11, 0xdf, 0xd8, 0xf6, + 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, 0x92, 0x1a, 0xf8, 0xf9, 0xd1, + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, 0xda, 0xbc, 0xbd, 0xbe, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, 0x02, 0xf7, 0x02, 0xf1, 0xbc, + 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, 0xfc, 0x3d, 0x00, 0x50, 0xf8, + /* bank # 18 */ + 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, + 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, 0xf9, 0xd1, 0xbb, 0x81, 0xaa, + 0xc1, 0xd9, 0xf4, 0x12, 0x47, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, 0xd9, 0xf4, 0x12, 0x47, 0xd8, + 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, 0xfd, 0x1e, 0xb7, 0x9a, 0x08, + 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, 0xa9, 0x80, 0xcd, 0xf2, 0xc4, + 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, 0x91, 0x72, 0x89, 0x91, 0x47, + 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x12, 0x75, 0xd8, 0xf3, + 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, 0xc3, 0xf2, 0xc5, 0xf3, 0xba, + 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, + 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, 0xbe, 0xb5, 0xb9, 0x97, 0xa5, + 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, 0x60, 0xf1, 0xbc, 0xb3, 0x8e, + 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9f, 0xf7, 0x5a, + 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, + 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, 0x9d, 0x60, 0x68, 0x70, 0x78, + 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xba, 0xa0, 0xd0, 0xf3, + 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, 0xd0, 0x64, 0x68, 0x9f, 0x60, + /* bank # 19 */ + 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, 0x85, 0x91, 0xa7, 0xf4, 0x75, + 0xa8, 0xf4, 0x75, 0xc0, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0xa8, 0xf0, 0xa2, 0x87, 0x0d, 0x20, + 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, 0x31, 0x48, 0xb8, 0xb1, 0xb4, + 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, 0x8f, 0x97, 0xf7, 0x02, 0xf9, + 0xda, 0xf4, 0x13, 0x7f, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x13, 0x78, + 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, 0x08, 0xf1, 0xa7, 0x84, 0x94, + 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, 0x81, 0x61, 0xd9, 0xf4, 0x13, + 0x97, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x97, 0xd8, 0xf1, 0xb8, 0xb2, 0xa6, 0x82, 0xc0, 0xd8, + 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, 0x04, 0xba, 0x87, 0x91, 0xa7, + 0xf4, 0x75, 0xb6, 0xb2, 0xf4, 0x75, 0xc0, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, + 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, 0x87, 0x91, 0xaf, 0xf4, 0x75, + 0xa8, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0x64, 0x19, 0x31, + 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, 0x8f, 0x91, 0xa7, 0xf4, 0x75, + 0xb6, 0xf4, 0x75, 0xc0, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, 0xb4, 0xba, 0x88, 0x9e, 0xa3, + 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, 0x50, 0x78, 0xb2, 0xb9, 0x8a, + 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, 0xa1, 0xc2, 0xc5, 0xba, 0xbc, + /* bank # 20 */ + 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xbd, 0xf4, 0x74, 0x9c, 0xf3, + 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x33, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, 0xba, + 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, 0x81, 0xc1, 0xc3, 0xf3, 0xa6, + 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, + 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x80, 0xad, 0xd0, 0xc0, + 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xf4, 0x74, 0x9c, + 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x84, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, + 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, 0xa9, 0x81, 0xc0, 0xc3, 0xf3, + 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, 0xd9, 0xf4, 0x15, 0x02, 0xd8, + 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, 0xb4, 0x84, 0x93, 0x69, 0xd9, + 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, 0xdf, 0xf8, 0xf4, 0x14, 0xcc, + 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, 0xf8, 0xd8, 0xf1, 0x94, 0xfc, + 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, 0x06, 0xfd, 0x1e, 0xa6, 0x81, + 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, 0xf5, 0x83, 0x93, 0x00, 0xa6, + 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, 0x81, 0x9b, 0xdb, 0x19, 0x8b, + /* bank # 21 */ + 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, + 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, 0xf4, 0x17, 0xa1, 0xd8, 0xf2, + 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, 0xde, 0xf8, 0xd8, 0xb2, 0x81, + 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb4, 0xf1, 0xac, 0x8c, 0x92, + 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, 0xad, 0xc0, 0xbe, 0xbe, 0xba, + 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, 0xde, 0xdf, 0xdf, 0xdf, 0xa5, + 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, 0x9c, 0x11, 0xd9, 0x8c, 0xc5, + 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, 0x9c, 0x45, 0xd9, 0x8f, 0xac, + 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, 0xaf, 0x8f, 0x9f, 0x59, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, 0xaf, 0x8f, 0x9f, 0x39, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, 0x8f, 0xbe, 0xbe, 0xba, 0xa1, + 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, 0xda, 0xf4, 0x17, 0x74, 0xd8, + 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, + 0x44, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xb1, 0xb6, + 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, 0x16, 0x1e, 0x8b, 0x9d, 0xab, + 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, 0xaa, 0x2c, 0x54, 0x7c, 0x9b, + /* bank # 22 */ + 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, 0x11, 0x8f, 0x19, 0xf4, 0x16, + 0x14, 0xd8, 0x17, 0x74, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb1, 0x8f, + 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, 0xad, 0x6d, 0xdb, 0x71, 0x79, + 0xf4, 0x16, 0x42, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, + 0x16, 0x51, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, 0xa1, 0xf8, 0xd9, 0xf4, 0x17, + 0x74, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xba, + 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, 0xc5, 0xb2, 0xb6, 0xa3, 0x87, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x86, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xc0, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x16, 0xd9, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, + 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, 0x9f, 0x02, 0xf4, 0x16, 0xd9, + 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, + 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, 0xb1, 0x8c, 0xad, 0xc1, 0xbe, + 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, 0xb2, 0xa0, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x80, + /* bank # 23 */ + 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x13, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, + 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xa7, 0x83, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, + 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0x83, 0xb5, + 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, 0xf2, 0xa1, 0xde, 0xf8, 0xf8, + 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0x8c, 0xad, 0xc0, 0xaf, 0x9c, + 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, + 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, 0x97, 0x01, 0xd1, 0xb9, 0xa7, + 0xc0, 0xda, 0xf4, 0x17, 0x8c, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x08, 0xbe, 0xbc, + 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, 0xb0, 0xaf, 0x9e, 0x88, 0x62, + 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0x85, 0xba, 0xb5, + 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, 0x81, 0x90, 0x2d, 0x55, 0x7d, + 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, 0xaf, 0x86, 0x9f, 0x69, 0xdb, + 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, + 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, 0xd8, 0xaf, 0x80, 0x90, 0x69, + /* bank # 24 */ + 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, + 0x19, 0xd1, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0xad, 0x8a, 0x9e, 0x26, + 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x17, 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, + 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0xaf, 0x8a, 0x9a, 0x21, 0x8f, + 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, + 0xa3, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, 0xd1, 0xf3, 0x91, 0xfc, 0xc0, + 0x07, 0xd9, 0xf4, 0x18, 0xa3, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, 0x01, 0xb3, 0xb5, 0x80, 0x97, + 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0xa3, 0xd8, 0xf3, 0xb9, 0xa7, 0xde, 0xf8, + 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x89, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, 0xc5, 0xc7, 0xf3, 0xa1, 0xde, + 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xa0, 0xd0, + 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, 0x55, 0x7d, 0xf5, 0xb5, 0xa8, + 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, 0x31, 0x39, 0xf4, 0x19, 0xe7, + 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, 0xa0, 0x81, 0x90, 0x2d, 0x55, + 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xba, 0xb0, + 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x84, 0xc0, 0xc3, 0xc5, + /* bank # 25 */ + 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, 0xac, 0x8c, 0xc2, 0xf3, 0xae, + 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x85, 0xc0, 0xc3, + 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, 0x86, 0x96, 0x06, 0xfd, 0x0f, + 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, 0x2e, 0xfd, 0x0f, 0x84, 0x9f, + 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, 0xdb, 0x71, 0x79, 0x8b, 0x9c, + 0x61, 0xf4, 0x19, 0x67, 0xda, 0x19, 0xe7, 0xd8, 0xf1, 0xab, 0x83, 0x91, 0x28, 0xfd, 0x05, 0x54, + 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, 0x8b, 0x95, 0x05, 0x2d, 0x55, + 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, 0xa2, 0xde, 0xf8, 0xf8, 0xf4, + 0x1a, 0x17, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, 0x8d, 0x9a, 0x01, 0xf5, 0x8f, + 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xe7, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, 0xae, 0x8b, 0xc1, 0xc3, 0xc5, + 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa9, 0x85, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, 0xc3, 0xc5, 0xc7, 0xf4, 0x19, + 0xe7, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, + 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, 0xdf, 0xba, 0xae, 0xde, 0xbb, + 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, 0xd1, 0xac, 0xc0, 0xd9, 0xae, + /* bank # 26 */ + 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbb, + 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, + 0x8c, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x49, 0xda, 0xc3, 0xc5, 0xd9, + 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, + 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, 0xb1, 0x89, 0xc2, 0xb3, 0xaf, + 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, 0xf3, 0xae, 0xdf, 0xf8, 0xf8, + 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, 0xdf, 0xf8, 0xfd, 0x0f, 0xad, + 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, 0xb7, 0x92, 0xfc, 0xc0, 0x04, + 0xd9, 0xf4, 0x18, 0x2b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x92, 0xd8, 0xf1, 0xd8, 0xf3, + 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x41, 0xd8, 0xf1, 0xaf, 0xde, 0xf9, + 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, 0x78, 0xfd, 0x0f, 0xf1, 0xa2, + 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, 0xfd, 0x0f, 0x0c, 0x30, 0xfd, + 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, 0x54, 0x7c, 0xaa, 0x82, 0x99, + 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, 0x0f, 0xac, 0x83, 0x9f, 0xf0, + 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, + 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, 0xc1, 0x82, 0xc1, 0xd8, 0xfc, + /* bank # 27 */ + 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xc5, 0x8a, 0xc5, + 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, 0xc7, 0xd8, 0xfc, 0xc0, 0x10, + 0xd9, 0xf4, 0x1b, 0xfb, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, 0x2e, 0xfd, 0x0f, 0xa0, 0xde, + 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, 0x8b, 0x90, 0x00, 0xb9, 0xa9, + 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xba, 0xb1, 0xb6, 0x89, 0xab, 0xc1, + 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, + 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, 0xc7, 0x84, 0xab, 0xd0, 0xc0, + 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, 0x30, 0xaa, 0x9a, 0x40, 0xd8, + 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, + 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x84, 0xab, 0xd0, 0xc4, + 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, + 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, 0xab, 0xd0, 0xc6, 0xaf, 0x8a, + 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x85, 0xab, + 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x30, 0xaa, 0x9a, + 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, + 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xf1, 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, + /* bank # 28 */ + 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, 0xfd, 0x0f, 0x46, 0xfd, 0x0f, + 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, 0x7c, 0xb6, 0x82, 0x92, 0xa0, + 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, 0xda, 0x82, 0xad, 0xc7, 0xd8, + 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x1b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x16, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, 0x89, 0x99, 0xaf, 0x31, 0xd9, + 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, 0xc2, 0xd8, 0x85, 0xaf, 0x49, + 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, 0xc6, 0xd8, 0x89, 0xaf, 0x39, + 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x89, 0xaa, 0x7c, 0xfd, 0x02, 0x9a, 0x68, + 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, 0x8f, 0x95, 0x25, 0x89, 0x9f, + 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x80, 0xd8, 0xf3, 0x9e, 0xfc, 0xc1, 0x04, 0xd9, 0xf4, 0x1b, + 0x48, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x63, 0xd8, 0xf1, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, + 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, 0xde, 0xd8, 0xbc, 0xbc, 0xf1, + 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, 0xa4, 0xde, 0xd8, 0xac, 0x88, + 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, 0x88, 0x95, 0xa4, 0xfc, 0x08, + 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, 0xf6, 0x02, 0xf8, 0xf9, 0xd1, + /* bank # 29 */ + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, 0x88, 0x92, 0x18, 0xbc, 0xbc, + 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, + 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, 0xd9, 0xf2, 0xac, 0x8c, 0x97, + 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, + 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xe1, 0xd8, 0xf1, 0xbe, 0xbe, 0xac, + 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x95, 0xfc, 0xc0, + 0x07, 0xda, 0xf4, 0x1e, 0x7c, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, 0x9c, 0xfc, 0xc1, 0x00, 0xf4, + 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, + 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, 0xf1, 0xbc, 0xbc, 0xbc, 0x80, + 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x9c, 0xda, 0xbc, 0x1e, 0x78, 0xd8, 0xf5, 0x86, 0x98, + 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, 0xf5, 0x5c, 0xd9, 0xf1, 0x82, + 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, 0xf4, 0x1d, 0xc9, 0xd8, 0xf1, + 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, 0x95, 0xf5, 0x1c, 0xd9, 0xf4, + 0x1e, 0x78, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, 0xac, 0x8c, 0x9c, 0x06, 0xd2, + 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, 0x28, 0xd3, 0x87, 0xd4, 0xa7, + 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, 0xac, 0x83, 0x90, 0x45, 0xd9, + /* bank # 30 */ + 0xf4, 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, 0x85, 0x66, 0xfd, 0x1d, 0x88, + 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, 0x81, 0x9c, 0xab, 0xd6, 0xfd, + 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, 0x8b, 0x98, 0xf5, 0x08, 0xd9, + 0xf4, 0x1e, 0x78, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x1e, + 0x50, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, 0xf8, 0xd8, 0xf4, 0x1e, 0x7c, + 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x74, 0xfd, 0x05, 0xa9, 0x94, + 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, 0x59, 0x84, 0xab, 0xc3, 0xc5, + 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, 0xdf, 0xd8, 0xf1, 0xa0, 0xde, + 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, 0xdf, 0xa2, 0x95, 0xfc, 0xc0, + 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, + 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, 0x01, 0xf3, 0xaa, 0xde, 0xf8, + 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, 0xd8, 0xac, 0x8a, 0x9a, 0x41, + 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xf4, 0x1e, 0xe1, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xa5, 0x85, 0x9c, + 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, 0xf9, 0xd9, 0xf4, 0x20, 0x18, + 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, 0x20, 0x18, 0xd8, 0xf1, 0xbc, + /* bank # 31 */ + 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, 0x84, 0xbd, 0xbd, 0xbd, 0xb7, + 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, 0x9f, 0x46, 0x8f, 0xa2, 0x0e, + 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, 0xfb, 0x86, 0x95, 0xaf, 0x29, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x4c, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, 0xda, 0xa6, 0xde, 0xf4, 0x1f, + 0x4c, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, 0xf8, 0xd8, 0xf1, 0x85, 0x94, + 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, 0x85, 0x96, 0xaf, 0x31, 0xd9, + 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, 0xa8, 0xdf, 0xa1, 0xde, 0x85, + 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, 0x97, 0xfc, 0xc0, 0x04, 0xdb, + 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x1f, 0xb4, 0xd8, + 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xdd, 0xd8, 0xf1, 0x93, 0xfc, 0xc0, 0x09, 0xd9, 0xa4, + 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, 0xa1, 0xc1, 0xa7, 0xde, 0xf8, + 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, 0x31, 0xdb, 0x9f, 0x71, 0x92, + 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, + 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, + 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, 0xa1, 0xc2, 0xd8, 0x93, 0xfc, + 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xa7, 0xfa, 0xa3, + /* bank # 32 */ + 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, + 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, 0xa7, 0xde, 0xf7, 0x84, 0x9f, + 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf0, 0xf7, 0xa7, 0x88, + 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf2, 0xbb, 0xa0, 0xf9, 0xda, 0xf4, 0x20, 0x48, + 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xdc, 0xd8, 0xf0, 0xb1, 0xb5, 0xba, 0x8a, 0x9a, 0xa7, + 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, 0xb2, 0xa7, 0x87, 0x90, 0x21, + 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, + 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, 0xa7, 0x82, 0x95, 0x65, 0xd1, + 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, 0xd1, 0xf4, 0x20, 0x98, 0xd8, + 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, 0xb2, 0xb6, 0x81, 0x96, 0xa1, + 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x8a, 0xaa, + 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x88, 0xa8, + 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, + 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, 0x93, 0xf6, 0x0a, 0xf2, 0xb4, + 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, 0xbe, 0xbb, 0xae, 0xf8, 0xf9, + 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + /* bank # 33 */ + 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, 0x85, 0x9e, 0xa5, 0x08, 0xd8, + 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, + 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, 0xb8, 0xb4, 0xf3, 0x98, 0xfc, + 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x86, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, + 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, 0x9a, 0xa7, 0x29, 0xd9, 0xa8, + 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, 0xa7, 0x51, 0xd9, 0xa8, 0xd0, + 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, 0xa7, 0x79, 0xd9, 0xa8, 0xd0, + 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, + 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x21, + 0xb6, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, + 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, 0x88, 0x9a, 0xa7, 0x01, 0xd9, + 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xd9, 0xf4, 0x21, + 0xfd, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, 0xde, 0xa4, 0x84, 0x9c, 0x3c, + 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9c, 0x34, 0xd8, 0xf2, + 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9e, 0x34, 0xd8, 0xa9, 0xd0, + 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9e, 0x24, 0xd8, 0xf1, 0xa7, + /* bank # 34 */ + 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, 0xf7, 0x85, 0x02, 0xf8, 0xf9, + 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, + 0x23, 0xf2, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, + 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, 0xdc, 0xd8, 0x85, 0x95, 0xa5, + 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0x80, 0xf0, + 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0xb1, 0x89, + 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x81, 0xf0, 0xdd, 0xf2, + 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, 0x86, 0xf0, 0xdd, 0xf1, 0xc2, + 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, + 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xb1, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0xb1, 0x8e, 0xf0, + 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, + 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0xd8, 0xf2, + 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, + 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x23, 0x74, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, 0xd9, 0xbe, 0xf2, 0xba, 0xae, + /* bank # 35 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, + 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, + 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, 0xb8, 0xa5, 0x00, 0xd9, 0xb3, + 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, + 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, + 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, + 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, 0xd0, 0xc0, 0xd8, 0x87, 0xf3, + 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x23, + 0x7d, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, 0xdf, 0xf3, 0x30, 0xfd, 0x08, + 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, + 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, 0xb5, 0x9f, 0x30, 0xa6, 0x39, + 0xd9, 0xf4, 0x23, 0xec, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, + 0x23, 0xdf, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, 0xd9, 0xf4, 0x23, 0xf2, 0xd8, + 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, 0xda, 0xf0, 0xe2, 0xf1, 0xb9, + 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, + /* bank # 36 */ + 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, 0xdf, 0xf7, 0x62, 0xf3, 0xf8, + 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, 0x9d, 0x66, 0x9e, 0x76, 0x9f, + 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, 0xf9, 0xda, 0xff, 0xd8, 0xb3, + 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, 0xf4, 0x25, 0xba, 0xd8, 0xf1, + 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, 0xc1, 0xf7, 0x88, 0xb4, 0x9d, + 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, 0x24, 0x8f, 0xd8, 0xf1, 0xb8, + 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xd9, + 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, + 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, 0xbe, 0xf4, 0x24, 0xf6, 0xd8, + 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xf5, 0x87, 0x95, 0xa7, 0x3a, + 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, + 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xaf, + 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, 0xa7, 0xde, 0xf8, 0xfd, 0x07, + 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, 0xd0, 0xde, 0x40, 0x48, 0x50, + 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, + 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, 0xc1, 0xbc, 0x84, 0xb8, 0xbe, + /* bank # 37 */ + 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, 0xbd, 0xda, 0xf4, 0x25, 0x43, + 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, 0xbc, 0x8e, 0xbe, 0xae, 0xd0, + 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, 0x40, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, + 0xf4, 0x25, 0xad, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xf5, 0x89, + 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, + 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, + 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, + 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, + 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, + 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, + 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb2, 0x80, 0xba, 0xa7, + 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x75, 0x8f, 0xb6, 0x9c, 0xf4, 0x75, 0x81, 0xaf, 0xf4, 0x75, + 0x87, 0x8b, 0xf4, 0x75, 0x75, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x81, 0xae, 0xf4, 0x75, 0x87, 0xb3, + 0x81, 0xf4, 0x75, 0x75, 0x85, 0x94, 0xf4, 0x75, 0x81, 0xbb, 0xa5, 0xf4, 0x75, 0x87, 0x80, 0xba, + 0xf4, 0x75, 0x75, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x81, 0xbb, 0xae, 0xf4, 0x75, 0x87, 0xb3, 0x83, + /* bank # 38 */ + 0xa3, 0xf4, 0x75, 0x93, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, + 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, 0x86, 0xaf, 0x42, 0x4e, 0x76, + 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, + 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, 0xd0, 0x3e, 0x80, 0x93, 0xaf, + 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, 0x83, 0x9b, 0xa7, 0x69, 0xdb, + 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x6d, 0xd8, 0xf1, 0xad, 0xde, 0xdf, 0xd8, 0xf0, 0xbc, + 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, 0x7c, 0x9b, 0x71, 0x97, 0xa5, + 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, 0xf5, 0xb0, 0x8c, 0xb7, 0x93, + 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, 0xba, 0x86, 0xa7, 0xc2, 0xf4, + 0x75, 0x9b, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, 0x81, 0xf1, 0xa4, 0xf4, 0x75, + 0x87, 0x83, 0xa3, 0xf4, 0x75, 0x93, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, 0x75, 0x9b, 0x95, 0xf0, 0x71, + 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x81, 0xa6, 0xf4, 0x75, 0x87, 0x85, 0xa5, 0xf4, 0x75, 0x93, + 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x9b, 0x9f, 0xf0, 0x71, 0x71, 0x60, 0x88, 0x92, 0xf4, 0x75, + 0x81, 0xa8, 0xf4, 0x75, 0x87, 0x8f, 0xaf, 0xf4, 0x75, 0x93, 0xf5, 0xb2, 0x84, 0x94, 0xb9, 0xaf, + /* bank # 39 */ + 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, 0x9f, 0xa5, 0x30, 0x85, 0x18, + 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xba, + 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, 0xa7, 0x87, 0xb6, 0x97, 0x2c, + 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, 0x97, 0x30, 0x9c, 0x1c, 0x97, + 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, 0x9c, 0x59, 0xdb, 0x51, 0xaa, + 0xde, 0xf4, 0x27, 0x6a, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, 0xfd, 0x02, 0xb2, 0x8b, 0x02, + 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, + 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xea, 0xd8, 0xf1, 0xb2, 0xbc, 0xbc, 0x84, 0xb8, + 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, + 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, 0x7c, 0x99, 0x71, 0x8a, 0x59, + 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xa9, 0xc2, + 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, 0x97, 0xaf, 0x09, 0x8f, 0xb5, + 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, 0xba, 0xa7, 0xc1, 0xc3, 0xc5, + 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0x77, 0xd8, 0xf1, 0xb2, + 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0xa1, 0x9a, 0xf4, 0x75, 0x81, 0x8a, 0xaa, 0xf4, + 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0xa1, 0x9c, 0xf4, 0x75, 0x81, 0x8c, + /* bank # 40 */ + 0xac, 0xf4, 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, 0x75, 0xa1, 0x9e, 0xf4, 0x75, + 0x81, 0x8e, 0xae, 0xf4, 0x75, 0x93, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, 0xc7, 0x87, 0xc3, 0x8b, 0xab, + 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, 0xc7, 0xb8, 0xae, 0xde, 0x8a, + 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, 0xfd, 0x01, 0xb0, 0xf0, 0x8d, + 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, 0x8d, 0x39, 0x9e, 0x7c, 0x9c, + 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, + 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, 0x50, 0xf1, 0x88, 0x98, 0xaf, + 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, 0xb4, 0xbc, 0xbc, 0xbc, 0x84, + 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, 0xaf, 0x49, 0xda, 0xf4, 0x28, + 0xa7, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xd9, + 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xb7, 0xd8, 0xf5, 0x91, 0x72, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, + 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xa0, 0xda, 0xf8, + 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, 0xfc, 0xc1, 0x04, 0xd9, 0xa1, + 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, 0xde, 0xdf, 0xa1, 0xdf, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, + 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, 0x21, 0xd9, 0xf4, 0x30, 0x31, + /* bank # 41 */ + 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, 0xdf, 0xdf, 0xab, 0xde, 0xac, + 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, 0xbe, 0xbe, 0xbe, 0x83, 0xa9, + 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x84, 0xd8, 0xf1, 0xaa, 0xde, 0x99, 0xfc, 0xc1, 0x00, + 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, 0xd8, 0xf5, 0xa2, 0x89, 0x92, + 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, 0x82, 0xdb, 0x31, 0xdf, 0xaa, + 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x71, + 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0xa8, 0xde, 0x98, + 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, 0xbe, 0x87, 0x94, 0xaf, 0x19, + 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x7a, 0xd8, 0xf1, 0x82, 0x9f, 0xaf, 0xdf, 0x28, 0xfd, 0x03, + 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, 0xde, 0xd9, 0xf8, 0xda, 0xf4, + 0x2a, 0xeb, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, 0xc7, 0x83, 0xa7, 0xd0, 0xc2, + 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, 0xb3, + 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, + 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, + /* bank # 42 */ + 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, + 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, + 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, + 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, 0xc7, 0xa0, 0xdf, 0xd0, 0xde, + 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, + 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0x8f, 0x93, 0xaf, 0x21, + 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, + 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, + 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, 0x2a, 0xba, 0xd8, 0xf3, 0xbc, + 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, 0xc5, 0xb1, 0xbc, 0x80, 0x93, + 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0x9f, 0xfc, 0xc1, 0x04, 0xf2, + 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, 0xf1, 0xa1, 0xd0, 0xde, 0x83, + 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xd4, 0xd8, 0xf2, 0x8f, 0x9f, 0x71, 0xd9, 0xf1, + 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, + 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0x82, 0x9d, 0xaf, + 0x31, 0xda, 0xf4, 0x2b, 0x1c, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, 0xb6, 0x9d, 0xfc, 0xc2, 0x04, + /* bank # 43 */ + 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0x88, 0xa4, + 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xba, 0xad, 0xf8, 0xf9, 0xd1, 0xd9, 0x83, 0xb9, + 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xf4, 0x2b, 0x5a, + 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0xa4, + 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, 0xf1, 0xb1, 0x85, 0xba, 0xbe, + 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, 0xa7, 0xdf, 0xdf, 0x8f, 0x92, + 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x9c, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, 0x2b, 0x83, 0xd8, 0xf1, 0xfa, + 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x90, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x93, 0x21, + 0xd9, 0xf4, 0x2b, 0xb0, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x59, 0xd9, 0xd0, 0xf8, 0xf4, + 0x2b, 0xcb, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, + 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, 0xc3, 0x04, 0xfc, 0xc0, 0x00, + 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, 0x94, 0xa7, 0x71, 0xd9, 0xf4, + /* bank # 44 */ + 0x2c, 0x14, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x14, 0xd8, 0xf1, 0x94, 0x09, 0xdb, 0x39, + 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, 0xbc, 0xbc, 0xbc, 0x83, 0xb9, + 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, 0x04, 0xd0, 0xd9, 0xc7, 0xda, + 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, 0xfc, 0xc1, 0x00, 0xd9, 0xf4, + 0x2c, 0xbb, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, 0x50, 0x78, 0xf1, 0xba, 0xaa, + 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, 0x8e, 0xbb, 0xab, 0xc7, 0xd8, + 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, 0x90, 0x79, 0xdb, 0xd1, 0xb9, + 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0xb0, 0xbc, 0x81, 0xb9, + 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, 0x2d, 0x8d, 0x9f, 0x31, 0xd9, + 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, 0xf5, 0x06, 0xf1, 0xdb, 0xfc, + 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf5, 0xb3, 0x89, 0xb7, + 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0x8f, 0xa9, 0xd0, + 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, + 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, + 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, + /* bank # 45 */ + 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, 0xa9, 0xc0, 0xd8, 0xa3, 0xde, + 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0xb9, + 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, 0xf4, 0x2d, 0x85, 0xd8, 0xf1, + 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, 0x8c, 0x95, 0x69, 0xd9, 0xdf, + 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x2d, 0x62, 0xd8, 0xf1, + 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, 0xd0, 0x80, 0x9c, 0x48, 0xd8, + 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, 0xb5, 0xd9, 0xa0, 0xd0, 0xde, + 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xa0, 0xd0, + 0xde, 0xd8, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf1, + 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, 0xfc, 0xc2, 0x00, 0xd9, 0xb2, + 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0x84, 0xb4, 0x9f, + 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0xae, 0xde, 0xd8, 0xf1, 0xb1, + 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, 0xb5, 0x9d, 0xa1, 0x02, 0xb7, + 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, 0x12, 0x26, 0x5e, 0x6e, 0xb3, + 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, 0x54, 0x7c, 0xaf, 0xde, 0xf8, + 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, 0x8a, 0xaa, 0xc4, 0xd8, 0x83, + /* bank # 46 */ + 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x4b, 0xd8, 0xf1, 0xa2, 0xd0, 0xde, 0xb6, 0x9e, 0xfc, 0xc0, + 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, 0xde, 0xfa, 0xb7, 0xbb, 0xf4, + 0x2e, 0x4b, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, 0x8d, 0x94, 0x1d, 0xf1, 0xe2, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, + 0x19, 0xd9, 0xf4, 0x2e, 0x8f, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, 0xf1, 0x8e, 0x91, 0x41, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, + 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0xa3, + 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, 0xc6, 0xf4, 0x2f, 0x0a, 0xd8, + 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, 0xaf, 0x59, 0xb3, 0xb7, 0xd1, + 0xd9, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, 0xa3, 0xf8, 0xad, 0xde, 0xd8, + 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xe5, 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, + 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0xad, 0xf8, 0xaf, 0xde, + 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, 0x9d, 0xaf, 0x21, 0xa3, 0xde, + 0xf8, 0xd8, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, 0xaf, 0x49, 0xda, 0xa3, 0xf8, + 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, + /* bank # 47 */ + 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, 0xf5, 0x83, 0x9a, 0xaf, 0x1a, + 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, 0xbc, 0xbc, 0xb1, 0x8b, 0x34, + 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, 0xd9, 0xf4, 0x2f, 0x64, 0xd8, + 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, + 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, + 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf5, 0x8e, 0xae, 0x32, 0xf1, + 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, + 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0xa6, 0xfa, 0x86, 0x96, 0xae, 0x39, 0xd9, + 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, + 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, + 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, 0xde, 0x85, 0xa5, 0xd0, 0xc6, + 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xe2, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0x60, 0xf3, + 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, 0xbe, 0xbe, 0x86, 0xa7, 0xc3, + 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, 0x0d, 0xf5, 0x99, 0xaf, 0x1a, + 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x4d, + /* bank # 48 */ + 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xf5, 0xa8, + 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, 0x38, 0x86, 0x9f, 0xaf, 0xde, + 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, 0xbc, 0xb1, 0x82, 0xc3, 0xbc, + 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, + 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, 0xf1, 0xb9, 0xac, 0xd9, 0xde, + 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, 0x40, 0x99, 0x6c, 0x97, 0x48, + 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, 0x83, 0x65, 0xd9, 0xf4, 0x30, + 0x94, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, 0xc3, 0xc1, 0xda, 0xc1, 0xc3, + 0xd8, 0xf4, 0x75, 0x55, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, + 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, 0xd9, 0xf5, 0xb3, 0x85, 0xb7, + 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, 0x1a, 0xf0, 0x96, 0x40, 0x9d, + 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, 0x0a, 0x8d, 0x96, 0x05, 0xd9, + 0xf4, 0x30, 0xfb, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, 0x49, 0xf9, 0xf9, 0xdb, 0xf1, + 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xfb, 0xd8, 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, + 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x0c, 0xd8, 0xf1, 0xb3, 0x85, 0xbb, + /* bank # 49 */ + 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, + 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, 0xde, 0xd8, 0xf2, 0xbb, 0xaf, + 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, 0xac, 0xd0, 0xc5, 0xf3, 0xa7, + 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, 0xc1, 0x00, 0xb8, 0xbe, 0xa7, + 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, 0x98, 0x19, 0xa9, 0x80, 0xd9, + 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf9, + 0xdf, 0xf8, 0xf4, 0x75, 0x3d, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, 0xf5, 0x75, 0xda, 0xff, 0xd8, + 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, 0xc2, 0xf1, 0x97, 0x86, 0x49, + 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, + 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, 0x70, 0x70, 0xf1, 0xd8, 0xb7, + 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, 0x2e, 0xd8, 0x89, 0x99, 0xaf, + 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, 0xdf, 0xd8, 0xaf, 0x82, 0xf3, + 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, 0x8f, 0x99, 0xaf, 0x51, 0xdb, + 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, 0x71, 0xd9, 0xf1, 0xdf, 0xf9, + 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, 0xbb, 0x82, 0xac, 0xf3, 0xc0, + 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, 0xac, 0xde, 0xff, 0xd8, 0xa2, + /* bank # 50 */ + 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, 0x81, 0xc5, 0xb0, 0xbc, 0xf1, + 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x33, 0xd8, 0xf2, 0x89, 0x99, 0xa9, + 0x49, 0xda, 0xf4, 0x32, 0x33, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, 0xa7, 0xd0, 0xd9, 0x88, 0x97, + 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, + 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, 0xbd, 0x9f, 0xba, 0xa7, 0x61, + 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, 0xb1, 0x84, 0xb6, 0x96, 0xba, + 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, 0xdb, 0xb3, 0x8d, 0xb6, 0x97, + 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, 0xb7, 0xbb, 0x97, 0x8c, 0xaf, + 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0xa6, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, 0x34, 0xaa, 0xd0, 0x8a, 0x50, + 0xf4, 0x75, 0x3d, 0xf4, 0x32, 0xc6, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, 0xb5, 0x9c, 0xfc, 0xc2, 0x07, + 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, 0x91, 0xa1, 0x6c, 0xaa, 0xd0, + 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x3d, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, 0x0a, 0xd9, 0xf4, 0x33, 0x07, + 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, 0xa6, 0xd0, 0x38, 0xfd, 0x31, + 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, 0x0f, 0x8d, 0x9f, 0x65, 0xd9, + 0xf4, 0x33, 0x07, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, 0x82, 0x9f, 0x25, 0xd9, 0xf1, + /* bank # 51 */ + 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xd9, 0xbc, + 0xbd, 0xbe, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, 0xde, 0xf2, 0xb3, 0x81, 0xb7, + 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, + 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, + 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xb0, 0x83, 0xb4, 0x93, + 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, 0x78, 0x8e, 0xbe, 0xb9, 0xaa, + 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf4, 0x33, 0xdf, + 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, 0x0c, 0x30, 0xba, 0x8d, 0x9d, + 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, 0x84, 0xb5, 0x94, 0xb9, 0xa4, + 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, + 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, 0x81, 0xb9, 0xa1, 0x34, 0xda, + 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, 0x4e, 0x81, 0xb9, 0xa1, 0x34, + 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, 0xd0, 0xdf, 0xf1, 0xff, 0xd8, + 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, 0x09, 0xaa, 0xd0, 0x8a, 0x9d, + 0xd9, 0x74, 0xf4, 0x33, 0xfa, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, + /* bank # 52 */ + 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, + 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, 0x61, 0xd9, 0xf2, 0xa1, 0xd0, + 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, 0x8f, 0xb7, 0x91, 0x15, 0xda, + 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, 0xb9, 0xac, 0xde, 0xad, 0xde, + 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf1, + 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, 0x91, 0xaf, 0x31, 0xd1, 0xd9, + 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, 0x8c, 0xb7, 0x9c, 0xbb, 0xac, + 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, 0xca, 0xf2, 0x91, 0x35, 0xf1, + 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, 0xa6, 0x8f, 0x96, 0x01, 0x8a, + 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, 0xff, 0xd8, 0xf0, 0xb9, 0xb1, + 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, 0x79, 0xe0, 0xd8, 0xf1, 0xba, + 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, 0x82, 0x90, 0x25, 0xf3, 0xad, + 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, 0x82, 0x38, 0xf1, 0xaa, 0x2d, + 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, 0x8f, 0x9f, 0x04, 0x28, 0x51, + 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, 0x9a, 0x2c, 0x50, 0x50, 0x78, + 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, 0xd8, 0xf1, 0xb8, 0xae, 0x82, + /* bank # 53 */ + 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, 0x81, 0xc1, 0xf3, 0xad, 0xfb, + 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xaa, 0x82, 0x9d, + 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, 0x54, 0x78, 0xfd, 0x7f, 0xf1, + 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, 0x9c, 0xe0, 0xd8, 0xf1, 0xb1, + 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, + 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, 0x85, 0xa5, 0xd0, 0xda, 0xc6, + 0xf4, 0x35, 0x72, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, 0xad, 0xd0, 0x8d, 0x9e, 0x7f, + 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, 0x93, 0xf0, 0x71, 0x71, 0x60, + 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xb6, 0x97, 0x2c, + 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, 0xf1, 0xb2, 0x81, 0x97, 0x66, + 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, + 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, 0x34, 0x49, 0x2d, 0x51, 0xe0, + 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x7f, + 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, 0xf4, 0x78, 0x59, 0x8d, 0xad, + 0xf4, 0x78, 0x59, 0x8e, 0xae, 0xf4, 0x78, 0x59, 0xbc, 0xb0, 0x80, 0xba, 0xaf, 0xf1, 0xde, 0xdf, + /* bank # 54 */ + 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, + 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, 0xbd, 0xb5, 0x90, 0xbb, 0xaf, + 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, 0x16, 0xf0, 0x38, 0x92, 0x40, + 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x36, 0x4a, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x1c, 0xd8, 0xf0, 0xb7, 0x8c, 0x9c, 0xba, + 0xf4, 0x78, 0x28, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8e, + 0x9e, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, + 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, 0xd0, 0x2a, 0xd2, 0xf0, 0x00, + 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, 0xa9, 0xf8, 0xd8, 0x97, 0xaf, + 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, + 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xc3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, + 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0x8f, 0x9e, 0x05, 0xda, 0xf4, + 0x36, 0xee, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, + 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, + 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, 0xf5, 0x00, 0xb1, 0x88, 0x04, + /* bank # 55 */ + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, + 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, 0xb1, 0x88, 0xd0, 0xf5, 0x44, + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, + 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x45, 0xd8, 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, + 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, 0xaf, 0x68, 0xd9, 0xaa, 0xfa, + 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, 0xfd, 0x40, 0x8f, 0xd0, 0xf5, + 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, 0xd0, 0xd9, 0xdf, 0xda, 0xfa, + 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, 0x9a, 0xd0, 0xf5, 0x04, 0xa9, + 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, + 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, 0x10, 0xaf, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, 0xbd, 0xf8, 0xf9, 0xd1, 0xda, + 0xf4, 0x37, 0xbd, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb1, + 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x41, 0xd9, + 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, 0xda, 0xf4, 0x37, 0xf2, 0xd8, + 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xf2, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x49, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, + /* bank # 56 */ + 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, + 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, 0x11, 0x3d, 0xf3, 0x15, 0x3d, + 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, 0xf1, 0xd4, 0xfd, 0x70, 0xd5, + 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, 0x10, 0x18, 0xf5, 0x00, 0xb5, + 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, + 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, 0xc9, 0xe0 \ No newline at end of file diff --git a/lib/ICM-20948/src/util/icm20948_img.dmp3a.h b/lib/ICM-20948/src/util/icm20948_img.dmp3a.h new file mode 100644 index 0000000..834203e --- /dev/null +++ b/lib/ICM-20948/src/util/icm20948_img.dmp3a.h @@ -0,0 +1,951 @@ + /* bank # 0 */ + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x05, 0x00, 0x01, 0x00, 0x05, 0x00, 0xff, + 0xff, 0xf7, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, 0x00, 0x05, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, 0x00, + 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, 0x00, + 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x40, 0x00, 0x20, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x01, + /* bank # 1 */ + 0x00, 0x00, 0x03, 0x84, 0x00, 0x00, 0x9c, 0x40, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x36, 0x66, 0x66, 0x66, 0x00, 0x0f, 0x00, 0x00, 0x13, 0x5c, 0x28, 0xf6, 0x0c, 0xf5, 0xc2, 0x8f, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xf8, 0x00, 0x38, + 0x09, 0xed, 0xd1, 0xe8, 0x00, 0x00, 0x68, 0x00, 0x00, 0x01, 0xff, 0xc7, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x3e, 0xb8, 0x51, 0xec, 0x00, 0x0f, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x0c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x15, 0x55, 0x55, 0x55, 0x0a, 0xaa, 0xaa, 0xaa, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xe1, 0x00, 0x00, 0x00, 0x01, 0x00, 0x06, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x48, 0xd1, 0x59, 0x3f, 0xb7, 0x2e, 0xa7, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x8e, 0x17, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, + /* bank # 2 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x00, 0x05, 0x21, 0xe9, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3e, 0x03, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x03, 0x00, 0x0a, 0x01, 0x2b, 0x4a, 0xee, + 0x06, 0x54, 0xad, 0x11, 0xe3, 0x07, 0x5c, 0x15, 0x36, 0x2b, 0xd0, 0x26, 0xd0, 0x8c, 0x49, 0xa4, + 0x06, 0x54, 0xad, 0x11, 0x1e, 0x0b, 0xb5, 0x55, 0x38, 0xee, 0x17, 0x50, 0x31, 0x36, 0x3f, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x0e, 0x35, 0x75, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0d, 0x72, 0xaa, 0x29, 0xc9, 0x3d, 0x6c, 0x4e, 0x55, 0x16, 0x4c, 0x7f, 0xc4, 0x42, 0x74, 0x97, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x15, 0xe3, 0xa3, 0x40, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0e, 0x70, 0x4b, 0x8c, 0xc5, 0x0a, 0x92, 0xbe, 0x5a, 0x96, 0x91, 0xd2, 0xc1, 0xee, 0xe7, 0x0d, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x14, 0x00, 0x2d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 4 */ + 0x00, 0x00, 0x00, 0xa3, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x3a, 0x03, 0xe8, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x26, 0x00, 0x00, 0x00, 0x02, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x3f, 0xc1, 0xa7, 0x68, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x33, 0x0c, 0xcc, 0xcc, 0xcd, + 0x00, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x18, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x64, 0x87, 0xed, 0x51, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x01, 0x1d, 0xf4, 0x6a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0x00, 0x00, 0x20, 0x00, + /* bank # 5 */ + 0x00, 0x00, 0x9c, 0x40, 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x07, 0x80, 0x00, 0x02, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0xb8, 0x51, 0xec, 0x01, 0x47, 0xae, 0x14, + 0x00, 0x00, 0x01, 0x5e, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x61, 0xa8, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x2e, 0xe0, 0x00, 0x06, 0x40, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x03, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x33, 0x33, 0x33, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0c, 0xcc, 0xcc, 0xcd, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x9d, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 6 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x49, 0x1b, 0x75, + 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x40, 0x00, 0x00, 0x0c, 0xcd, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 7 */ + 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x00, 0x46, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x01, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 8 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x3a, 0x98, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x4e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x47, 0xae, 0x14, 0x4e, 0x40, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x00, 0x00, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0d, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x4a, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xd8, 0x00, 0x00, 0x01, 0x18, 0x00, 0x00, 0x07, 0xd0, + /* bank # 9 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x27, 0x10, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x13, 0x1b, + 0x00, 0x0b, 0xb8, 0x00, 0x00, 0x3c, 0xbf, 0x0f, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x27, 0x10, + 0x05, 0xb0, 0x5b, 0x05, 0x3a, 0x4f, 0xa4, 0xfa, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0x00, 0x1d, 0x20, 0x8a, 0x00, 0x61, 0x93, 0x69, + 0x00, 0x00, 0x01, 0x3c, 0x00, 0x00, 0x4d, 0xf0, 0x00, 0x55, 0xce, 0x75, 0x00, 0x00, 0x02, 0x76, + 0x06, 0x66, 0x66, 0x66, 0x39, 0x99, 0x99, 0x99, 0x10, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcc, 0xcc, 0xcc, 0x33, 0x33, 0x33, 0x33, 0x00, 0x0e, 0x90, 0x45, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x3e, 0x2b, 0xe2, 0xbf, 0x3f, 0xf1, 0x6f, 0xbb, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x93, 0x87, 0x00, 0x01, 0x24, 0x92, 0x49, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x98, 0x96, 0x80, 0x08, 0x58, 0x3b, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xaf, 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x00, 0x01, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 10 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, + 0x3f, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x1c, 0xfa, 0x77, + 0x0c, 0x6d, 0x39, 0xe6, 0xcb, 0x6f, 0xda, 0xa6, 0x53, 0xcf, 0xd3, 0x97, 0xc4, 0x53, 0x74, 0x46, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xda, 0x74, 0x0e, 0x3f, 0x25, 0x8b, 0xf2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x1d, 0x4c, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 11 */ + 0x20, 0x00, 0x00, 0x00, 0x3e, 0x2b, 0xe2, 0xbf, 0x3e, 0x14, 0x7a, 0xe2, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x07, 0xd0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x13, 0x88, 0x3c, 0x23, 0xec, 0x84, + 0x20, 0x00, 0x00, 0x00, 0x01, 0xd4, 0x1d, 0x41, 0x01, 0xeb, 0x85, 0x1e, 0x10, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x00, 0x00, 0x34, 0x6c, 0xfc, 0xb2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, + 0x00, 0x00, 0x17, 0x70, 0x00, 0x00, 0x13, 0x88, 0x00, 0x00, 0x23, 0x28, 0x00, 0x00, 0x00, 0x26, + 0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0xc4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x01, 0xeb, 0x85, 0x1e, 0x3e, 0x14, 0x7a, 0xe2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2d, 0x02, 0x22, 0x22, 0x22, 0x3d, 0xdd, 0xdd, 0xde, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0xb8, 0x3d, 0xd1, 0xba, 0x8e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 12 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xd6, 0x00, 0x00, 0x83, 0xd6, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x21, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x30, 0xfc, 0xf9, 0x40, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x80, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x0a, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x33, 0x33, 0x00, 0x0c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x31, 0x88, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf0, 0xde, 0x9a, 0xf8, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x90, 0xb2, 0x83, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xf7, 0x21, 0x8c, 0xd5, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0x6f, 0x39, 0x95, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 13 */ + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, + 0x00, 0x53, 0x44, 0x00, 0x00, 0x53, 0x44, 0x00, 0x01, 0x9a, 0x00, 0x00, 0x01, 0x9a, 0x00, 0x00, + 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x05, 0x46, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0x19, + 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x02, 0x58, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x01, 0x2c, 0x00, 0x00, 0x00, 0x96, + 0x00, 0xcf, 0x50, 0xa4, 0x00, 0xcf, 0x50, 0xa4, 0x01, 0x35, 0xd0, 0xa4, 0x01, 0x35, 0xd0, 0xa4, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, + 0x00, 0x0c, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 14 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x7b, 0xab, 0x50, 0x01, 0x2d, 0xb6, 0x48, 0x00, 0x00, 0x16, 0xac, 0x00, 0x22, 0x82, 0x60, + 0x00, 0x00, 0x11, 0x8b, 0x04, 0x4c, 0xcc, 0xb0, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x16, 0x81, + 0x02, 0x78, 0xfe, 0xe0, 0x03, 0x94, 0x3a, 0xb0, 0x00, 0x10, 0xb4, 0x90, 0x00, 0x00, 0x03, 0x2a, + 0x00, 0x00, 0x25, 0xf6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x10, 0x00, + 0x08, 0x52, 0xdf, 0x89, 0x05, 0x8c, 0x95, 0x06, 0x01, 0x63, 0x25, 0x41, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x7b, 0x47, 0x69, 0x02, 0xe5, 0xdb, 0xae, 0x06, 0xf1, 0x85, 0x78, 0x07, 0xdf, 0xab, 0x88, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 15 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfe, 0x4c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x99, 0x99, 0x9a, 0x00, 0x66, 0x66, 0x66, + 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x1e, + 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x66, 0x66, 0x66, 0x00, 0x04, 0xd4, 0x5e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x1e, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x96, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xf8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 16 */ + 0xd8, 0xdc, 0xb8, 0xb0, 0xb4, 0xf3, 0xaa, 0xf8, 0xf9, 0xd1, 0xd9, 0x88, 0x9a, 0xf8, 0xf7, 0x3e, + 0xd8, 0xf3, 0x8a, 0x9a, 0xa7, 0x31, 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x9f, 0x39, 0xf9, + 0xd1, 0xd9, 0xf4, 0x10, 0x36, 0xd8, 0xf3, 0x8f, 0x9f, 0x08, 0x97, 0x60, 0x8a, 0x21, 0xd1, 0xd9, + 0xf4, 0x10, 0x36, 0xda, 0xf1, 0xff, 0xd8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xba, 0xb2, + 0xb6, 0xa0, 0x80, 0x90, 0x32, 0x18, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa4, + 0xdf, 0xa5, 0xde, 0xf3, 0xa8, 0xde, 0xd0, 0xdf, 0xa4, 0x84, 0x9f, 0x24, 0xf2, 0xa9, 0xf8, 0xf9, + 0xd1, 0xda, 0xde, 0xa8, 0xde, 0xdf, 0xdf, 0xdf, 0xd8, 0xf4, 0xb1, 0x8d, 0xf3, 0xa8, 0xd0, 0xb0, + 0xb4, 0x8f, 0xf4, 0xb9, 0xaf, 0xd0, 0xc7, 0xbe, 0xbe, 0xb8, 0xae, 0xd0, 0xf3, 0x9f, 0x75, 0xb2, + 0x86, 0xf4, 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc3, 0xf1, 0xbe, 0xb8, 0xb0, 0xa3, 0xde, 0xdf, 0xdf, + 0xdf, 0xf2, 0xa3, 0x81, 0xc0, 0x80, 0xcd, 0xc7, 0xcf, 0xbc, 0xbd, 0xb4, 0xf1, 0xa3, 0x8d, 0x93, + 0x20, 0xfd, 0x3f, 0x88, 0x6e, 0x76, 0x7e, 0x8d, 0x93, 0xbe, 0xa2, 0x20, 0xfd, 0x31, 0xa0, 0x2c, + 0xfd, 0x32, 0x34, 0xfd, 0x32, 0x3c, 0xfd, 0x32, 0xbe, 0xb9, 0xac, 0x8d, 0x20, 0xb8, 0xbe, 0xbe, + 0xbc, 0xa2, 0x86, 0x9d, 0x08, 0xfd, 0x0f, 0xbc, 0xbc, 0xbc, 0xa3, 0x82, 0x93, 0x01, 0xa9, 0x83, + 0x9e, 0x0e, 0x16, 0x1e, 0xbe, 0xbe, 0xbe, 0xbc, 0xa5, 0x8b, 0x99, 0x2c, 0x54, 0x7c, 0xbc, 0xbc, + 0x85, 0x93, 0xba, 0xa5, 0x2d, 0x55, 0x7d, 0xb8, 0xa5, 0x9d, 0x2c, 0xfd, 0x37, 0x4c, 0xfd, 0x37, + 0x6c, 0xfd, 0x37, 0xf5, 0xa5, 0x85, 0x9f, 0x34, 0x54, 0x74, 0xbd, 0xbd, 0xbd, 0xb1, 0xb6, 0xba, + /* bank # 17 */ + 0x83, 0x95, 0xa5, 0xf1, 0x0e, 0x16, 0x1e, 0xb2, 0xa7, 0x85, 0x95, 0x2a, 0xf0, 0x50, 0x78, 0x87, + 0x93, 0xf1, 0x01, 0xda, 0xa5, 0xdf, 0xdf, 0xdf, 0xd8, 0xa4, 0xdf, 0xdf, 0xdf, 0xb0, 0x80, 0xf2, + 0xa4, 0xc3, 0xcb, 0xc5, 0xf1, 0xb1, 0x8e, 0x94, 0xa4, 0x0e, 0x16, 0x1e, 0xb2, 0x86, 0xbe, 0xa0, + 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb4, 0x96, 0xb8, 0xa1, 0x2c, 0x34, 0x3c, 0xbd, 0xbd, 0xb6, 0x94, + 0xbe, 0xa6, 0x2c, 0xfd, 0x35, 0x34, 0xfd, 0x35, 0x3c, 0xfd, 0x35, 0xbc, 0xb2, 0x8e, 0x94, 0xb8, + 0xbe, 0xbe, 0xa6, 0x2d, 0x55, 0x7d, 0xba, 0xa4, 0x2d, 0x55, 0x7d, 0xb8, 0xb0, 0xb4, 0xa6, 0x8f, + 0x96, 0x2e, 0x36, 0x3e, 0xbc, 0xbc, 0xbc, 0xbd, 0xa6, 0x86, 0x9f, 0xf5, 0x34, 0x54, 0x74, 0xbc, + 0xbe, 0xf1, 0x90, 0xfc, 0xc3, 0x00, 0xd9, 0xf4, 0x11, 0xdf, 0xd8, 0xf3, 0xa0, 0xdf, 0xf1, 0xbc, + 0x86, 0x91, 0xa9, 0x2d, 0x55, 0x7d, 0xbc, 0xbc, 0xbc, 0xa9, 0x80, 0x90, 0xfc, 0x51, 0x00, 0x10, + 0xfc, 0x51, 0x00, 0x10, 0xfc, 0x51, 0x00, 0x10, 0xfc, 0xc1, 0x04, 0xd9, 0xf2, 0xa0, 0xdf, 0xf4, + 0x11, 0xdf, 0xd8, 0xf6, 0xa0, 0xfa, 0x80, 0x90, 0x38, 0xf3, 0xde, 0xda, 0xf8, 0xf4, 0x11, 0xdf, + 0xd8, 0xf1, 0xbd, 0x95, 0xfc, 0xc1, 0x04, 0xd9, 0xbd, 0xbd, 0xbd, 0xf4, 0x11, 0xdf, 0xd8, 0xf6, + 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xb5, 0xa7, 0x84, 0x92, 0x1a, 0xf8, 0xf9, 0xd1, + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xb6, 0x87, 0x96, 0xf3, 0x09, 0xff, 0xda, 0xbc, 0xbd, 0xbe, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xf6, 0xb0, 0x82, 0xb4, 0x97, 0xb8, 0xa9, 0x02, 0xf7, 0x02, 0xf1, 0xbc, + 0x89, 0x99, 0xa7, 0x04, 0xfd, 0x37, 0xa8, 0xdf, 0x87, 0x98, 0xa7, 0xfc, 0x3d, 0x00, 0x50, 0xf8, + /* bank # 18 */ + 0xf9, 0xd1, 0xd9, 0xa8, 0xdf, 0xf9, 0xd8, 0xf6, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, + 0xbe, 0xb7, 0xa7, 0x81, 0x9a, 0x0b, 0xb4, 0x87, 0x9f, 0x1a, 0xf8, 0xf9, 0xd1, 0xbb, 0x81, 0xaa, + 0xc1, 0xd9, 0xf4, 0x12, 0x47, 0xd8, 0xf6, 0xb8, 0xa7, 0x1a, 0xf9, 0xd9, 0xf4, 0x12, 0x47, 0xd8, + 0x8a, 0xf3, 0xbb, 0xaa, 0xc0, 0xc3, 0xb3, 0xaa, 0x8a, 0x9d, 0x1a, 0xfd, 0x1e, 0xb7, 0x9a, 0x08, + 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9d, 0x00, 0xd8, 0xf3, 0xb9, 0xb2, 0xa9, 0x80, 0xcd, 0xf2, 0xc4, + 0xc5, 0xba, 0xf3, 0xa0, 0xd0, 0xde, 0xb1, 0xb4, 0xf7, 0xa7, 0x89, 0x91, 0x72, 0x89, 0x91, 0x47, + 0xb6, 0x97, 0x4a, 0xb9, 0xf2, 0xa9, 0xd0, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x12, 0x75, 0xd8, 0xf3, + 0xba, 0xa7, 0xf9, 0xdb, 0xfb, 0xd9, 0xf1, 0xb9, 0xb0, 0x81, 0xa9, 0xc3, 0xf2, 0xc5, 0xf3, 0xba, + 0xa0, 0xd0, 0xf8, 0xd8, 0xf1, 0xb1, 0x89, 0xa7, 0xdf, 0xdf, 0xdf, 0xf2, 0xa7, 0xc3, 0xcb, 0xc5, + 0xf1, 0xb2, 0x87, 0xb8, 0xbe, 0xbe, 0xbe, 0xab, 0xc2, 0xc5, 0xc7, 0xbe, 0xb5, 0xb9, 0x97, 0xa5, + 0x22, 0xf0, 0x48, 0x70, 0x3c, 0x98, 0x40, 0x68, 0x34, 0x58, 0x99, 0x60, 0xf1, 0xbc, 0xb3, 0x8e, + 0x95, 0xaa, 0x25, 0x4d, 0x75, 0xbc, 0xbc, 0xbc, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9f, 0xf7, 0x5a, + 0xf9, 0xda, 0xf3, 0xa8, 0xf8, 0x88, 0x9d, 0xd0, 0x7c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, + 0xda, 0xf3, 0xa8, 0x88, 0x9c, 0xd0, 0xdf, 0x60, 0x68, 0x70, 0x78, 0x9d, 0x60, 0x68, 0x70, 0x78, + 0x9e, 0x70, 0x78, 0x9f, 0x70, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xba, 0xa0, 0xd0, 0xf3, + 0xd9, 0xde, 0xd8, 0xf8, 0xf9, 0xd1, 0xb8, 0xda, 0xa8, 0x88, 0x9e, 0xd0, 0x64, 0x68, 0x9f, 0x60, + /* bank # 19 */ + 0xd8, 0xa8, 0x84, 0x98, 0xd0, 0xf7, 0x7e, 0xf1, 0xb2, 0xb6, 0xba, 0x85, 0x91, 0xa7, 0xf4, 0x75, + 0xa8, 0xf4, 0x75, 0xc0, 0xf1, 0x84, 0x91, 0xa7, 0xf4, 0x75, 0xa8, 0xf0, 0xa2, 0x87, 0x0d, 0x20, + 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0xa4, 0xf1, 0x62, 0xf0, 0x19, 0x31, 0x48, 0xb8, 0xb1, 0xb4, + 0xf1, 0xa6, 0x80, 0xc6, 0xf4, 0xb0, 0x81, 0xf3, 0xa7, 0xc6, 0xb1, 0x8f, 0x97, 0xf7, 0x02, 0xf9, + 0xda, 0xf4, 0x13, 0x7f, 0xd8, 0xb0, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x13, 0x78, + 0xd8, 0xf1, 0xb2, 0xb6, 0xa6, 0x82, 0x92, 0x2a, 0xf0, 0x50, 0xfd, 0x08, 0xf1, 0xa7, 0x84, 0x94, + 0x02, 0xfd, 0x08, 0xb0, 0xb4, 0x86, 0x97, 0x00, 0xb1, 0xba, 0xa7, 0x81, 0x61, 0xd9, 0xf4, 0x13, + 0x97, 0xd8, 0xf1, 0x41, 0xda, 0xf4, 0x13, 0x97, 0xd8, 0xf1, 0xb8, 0xb2, 0xa6, 0x82, 0xc0, 0xd8, + 0xf1, 0xb0, 0xb6, 0x86, 0x92, 0xa7, 0x16, 0xfd, 0x04, 0x0f, 0xfd, 0x04, 0xba, 0x87, 0x91, 0xa7, + 0xf4, 0x75, 0xb6, 0xb2, 0xf4, 0x75, 0xc0, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbd, 0xbd, 0xbd, 0xb2, + 0xba, 0x84, 0xa7, 0xc3, 0xc5, 0xc7, 0xb2, 0xbc, 0xbc, 0xbc, 0xb6, 0x87, 0x91, 0xaf, 0xf4, 0x75, + 0xa8, 0xa0, 0x8f, 0xf1, 0x0b, 0xf0, 0x20, 0x59, 0x70, 0x15, 0x38, 0x40, 0x69, 0x64, 0x19, 0x31, + 0x48, 0xf1, 0x80, 0x90, 0xaf, 0x6e, 0xfd, 0x04, 0x67, 0xfd, 0x04, 0x8f, 0x91, 0xa7, 0xf4, 0x75, + 0xb6, 0xf4, 0x75, 0xc0, 0xf1, 0xbe, 0xbc, 0xbd, 0xf7, 0xbe, 0xb0, 0xb4, 0xba, 0x88, 0x9e, 0xa3, + 0x6a, 0x9f, 0x66, 0xf0, 0xb1, 0xb5, 0xb9, 0x8a, 0x9a, 0xa2, 0x2c, 0x50, 0x78, 0xb2, 0xb9, 0x8a, + 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x89, 0xad, 0xd0, 0xc4, 0xc7, 0x83, 0xa1, 0xc2, 0xc5, 0xba, 0xbc, + /* bank # 20 */ + 0xbc, 0xbc, 0xb2, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xbd, 0xf4, 0x74, 0x9c, 0xf3, + 0xba, 0xa3, 0xfa, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x33, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, 0xba, + 0xb1, 0x82, 0xa3, 0xd0, 0xc7, 0xa9, 0xd0, 0x8d, 0xc4, 0xc7, 0xa3, 0x81, 0xc1, 0xc3, 0xf3, 0xa6, + 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xaa, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, + 0xbe, 0xbc, 0xbc, 0xbc, 0xb2, 0xb9, 0x88, 0xaf, 0xc0, 0xc3, 0xc5, 0xc7, 0x80, 0xad, 0xd0, 0xc0, + 0xc3, 0x89, 0xa1, 0xc0, 0xc3, 0xba, 0x81, 0xa2, 0xc0, 0xc3, 0xc5, 0xc7, 0xbc, 0xf4, 0x74, 0x9c, + 0xf3, 0xba, 0xa3, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x14, 0x84, 0xd8, 0x74, 0xad, 0xbe, 0xbe, 0xbe, + 0xb8, 0xb1, 0x82, 0xa7, 0xd0, 0xc7, 0xba, 0xa0, 0x8d, 0xc4, 0xc7, 0xa9, 0x81, 0xc0, 0xc3, 0xf3, + 0xa5, 0x8d, 0xc2, 0xbe, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xba, 0xb1, 0xa8, 0x8f, 0xc0, 0xc3, 0xc5, + 0xc7, 0xbe, 0xf3, 0xba, 0xb2, 0xb6, 0xa3, 0x83, 0x93, 0x08, 0xf9, 0xd9, 0xf4, 0x15, 0x02, 0xd8, + 0xf0, 0xb8, 0xb0, 0xa3, 0x85, 0x94, 0x04, 0x28, 0x50, 0x78, 0xf1, 0xb4, 0x84, 0x93, 0x69, 0xd9, + 0xb6, 0xa5, 0x8d, 0x94, 0x20, 0x2c, 0x34, 0x3c, 0xb4, 0xa4, 0xde, 0xdf, 0xf8, 0xf4, 0x14, 0xcc, + 0xd8, 0xf1, 0xa4, 0xf8, 0xa3, 0x84, 0x94, 0x41, 0xd9, 0xa4, 0xdf, 0xf8, 0xd8, 0xf1, 0x94, 0xfc, + 0xc1, 0x04, 0xd9, 0xa4, 0xfb, 0xa3, 0x86, 0xc0, 0xb1, 0x82, 0x9e, 0x06, 0xfd, 0x1e, 0xa6, 0x81, + 0x96, 0x42, 0x93, 0xf0, 0x68, 0xb0, 0xa3, 0xf1, 0x83, 0x96, 0x01, 0xf5, 0x83, 0x93, 0x00, 0xa6, + 0x86, 0x96, 0xf0, 0x34, 0x83, 0x18, 0xf1, 0xa1, 0x8d, 0x68, 0xa3, 0x81, 0x9b, 0xdb, 0x19, 0x8b, + /* bank # 21 */ + 0xa1, 0xc6, 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xd8, 0xf7, 0xb8, + 0xb4, 0xb0, 0xa7, 0x9d, 0x88, 0x72, 0xf9, 0xbc, 0xbd, 0xbe, 0xd9, 0xf4, 0x17, 0xa1, 0xd8, 0xf2, + 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xba, 0xa1, 0xde, 0xae, 0xde, 0xf8, 0xd8, 0xb2, 0x81, + 0xbe, 0xbe, 0xb9, 0xaf, 0xd0, 0xc1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, 0xb4, 0xf1, 0xac, 0x8c, 0x92, + 0x0a, 0x18, 0xb5, 0xaf, 0x8c, 0x9d, 0x41, 0xdb, 0x9c, 0x11, 0x8e, 0xad, 0xc0, 0xbe, 0xbe, 0xba, + 0xae, 0xc3, 0xc5, 0xc7, 0x8d, 0xa8, 0xc6, 0xc7, 0xc7, 0xc7, 0xa6, 0xde, 0xdf, 0xdf, 0xdf, 0xa5, + 0xd0, 0xde, 0xdf, 0xbe, 0xbe, 0xd8, 0xb9, 0xac, 0xdf, 0xaf, 0x8d, 0x9c, 0x11, 0xd9, 0x8c, 0xc5, + 0xda, 0xc1, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0x8c, 0x9c, 0x45, 0xd9, 0x8f, 0xac, + 0xc1, 0xd8, 0xf2, 0xaf, 0xdf, 0xf8, 0xf8, 0xdf, 0xf8, 0xf8, 0xf8, 0xaf, 0x8f, 0x9f, 0x59, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x31, 0xf2, 0x8f, 0xaf, 0xd0, 0xc3, 0xd8, 0xaf, 0x8f, 0x9f, 0x39, 0xd1, + 0xdb, 0xf1, 0x8c, 0x9c, 0x69, 0xf2, 0x8f, 0xaf, 0xd0, 0xc5, 0xd8, 0x8f, 0xbe, 0xbe, 0xba, 0xa1, + 0xc6, 0xbc, 0xbc, 0xbd, 0xbd, 0xf2, 0xb1, 0xb5, 0xb9, 0xae, 0xf9, 0xda, 0xf4, 0x17, 0x74, 0xd8, + 0xf2, 0x8e, 0xc2, 0xf1, 0xb2, 0x80, 0x9a, 0xf5, 0xaf, 0x24, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, + 0x44, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf5, 0x64, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xb1, 0xb6, + 0x8b, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb5, 0x8c, 0x9f, 0xad, 0x0e, 0x16, 0x1e, 0x8b, 0x9d, 0xab, + 0x2c, 0x54, 0x7c, 0x8d, 0x9f, 0xaa, 0x2e, 0x56, 0x7e, 0x8a, 0x9c, 0xaa, 0x2c, 0x54, 0x7c, 0x9b, + /* bank # 22 */ + 0xac, 0x26, 0x46, 0x66, 0xaf, 0x8d, 0x9d, 0x00, 0x9c, 0x0d, 0xdb, 0x11, 0x8f, 0x19, 0xf4, 0x16, + 0x14, 0xd8, 0x17, 0x74, 0xd8, 0xf1, 0xb2, 0x81, 0xb6, 0x90, 0xaf, 0x2d, 0x55, 0x7d, 0xb1, 0x8f, + 0xb5, 0x9f, 0xaf, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xb2, 0x8c, 0x9f, 0xad, 0x6d, 0xdb, 0x71, 0x79, + 0xf4, 0x16, 0x42, 0xd8, 0xf3, 0xba, 0xa1, 0xde, 0xf8, 0xf1, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf4, + 0x16, 0x51, 0xd8, 0xf3, 0xb6, 0xba, 0x91, 0xfc, 0xc0, 0x28, 0xda, 0xa1, 0xf8, 0xd9, 0xf4, 0x17, + 0x74, 0xd8, 0xf3, 0xb9, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf8, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0xba, + 0xb1, 0xb5, 0xa0, 0x8b, 0x93, 0x3e, 0x5e, 0x7e, 0xab, 0x83, 0xc0, 0xc5, 0xb2, 0xb6, 0xa3, 0x87, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x86, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa5, 0x85, 0xc4, 0xc7, 0xac, 0x8d, 0xc0, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, + 0xad, 0xd0, 0xde, 0xaf, 0x8c, 0x9c, 0x41, 0xd9, 0xf4, 0x16, 0xc0, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x16, 0xd9, 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xda, 0x8c, 0xc5, 0xd9, 0xc3, 0xd8, + 0xaf, 0x8f, 0x21, 0xf5, 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x82, 0x9f, 0x02, 0xf4, 0x16, 0xd9, + 0xd8, 0xf1, 0xaf, 0x8d, 0x9c, 0x31, 0xd9, 0x8c, 0xc5, 0xda, 0xc3, 0xd8, 0xaf, 0x8f, 0x21, 0xf5, + 0x9f, 0x00, 0xf1, 0xad, 0xd0, 0xb0, 0x83, 0x9f, 0x02, 0xd8, 0xf1, 0xb1, 0x8c, 0xad, 0xc1, 0xbe, + 0xbe, 0xbd, 0xbd, 0xba, 0xb6, 0xac, 0x8d, 0x9c, 0x40, 0xbc, 0xbc, 0xb2, 0xa0, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xfd, 0x0f, 0xf5, 0xaf, 0x88, 0x98, 0x00, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x80, + /* bank # 23 */ + 0x9f, 0x01, 0xdb, 0x09, 0x11, 0x19, 0xf4, 0x17, 0x13, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, + 0xf1, 0xac, 0xde, 0xd8, 0xf3, 0xae, 0xde, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xa7, 0x83, 0xc0, + 0xc3, 0xc5, 0xc7, 0xa8, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, + 0x85, 0xd0, 0xc0, 0xc3, 0x8d, 0x9d, 0xaf, 0x39, 0xd9, 0xf4, 0x17, 0x74, 0xd8, 0xf1, 0x83, 0xb5, + 0x9e, 0xae, 0x34, 0xfd, 0x0a, 0x54, 0xfd, 0x0a, 0x74, 0xfd, 0x0a, 0xf2, 0xa1, 0xde, 0xf8, 0xf8, + 0xf8, 0xf1, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb1, 0xb5, 0x8c, 0xad, 0xc0, 0xaf, 0x9c, + 0x11, 0xd9, 0xae, 0xc0, 0xbc, 0xbc, 0xb2, 0x8e, 0xc3, 0xc5, 0xc7, 0xbc, 0xbc, 0xd8, 0xbe, 0xbe, + 0xbc, 0xbc, 0xbd, 0xbd, 0xd8, 0xf2, 0xba, 0xb2, 0xb5, 0xaf, 0x81, 0x97, 0x01, 0xd1, 0xb9, 0xa7, + 0xc0, 0xda, 0xf4, 0x17, 0x8c, 0xd8, 0xf2, 0xba, 0xae, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x08, 0xbe, 0xbc, + 0xbd, 0xd8, 0xf7, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbb, 0xb4, 0xb0, 0xaf, 0x9e, 0x88, 0x62, + 0xf9, 0xbc, 0xbd, 0xd9, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0x85, 0xba, 0xb5, + 0xa0, 0x98, 0x06, 0x26, 0x46, 0xbc, 0xb9, 0xb3, 0xb6, 0xf1, 0xaf, 0x81, 0x90, 0x2d, 0x55, 0x7d, + 0xb1, 0xb5, 0xaf, 0x8f, 0x9f, 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xbb, 0xaf, 0x86, 0x9f, 0x69, 0xdb, + 0x71, 0x79, 0xda, 0xf3, 0xa0, 0xdf, 0xf8, 0xf1, 0xa1, 0xde, 0xf2, 0xf8, 0xd8, 0xb3, 0xb7, 0xf1, + 0x8c, 0x9b, 0xaf, 0x19, 0xd9, 0xac, 0xde, 0xf3, 0xa0, 0xdf, 0xf8, 0xd8, 0xaf, 0x80, 0x90, 0x69, + /* bank # 24 */ + 0xd9, 0xa0, 0xfa, 0xf1, 0xb2, 0x80, 0xa1, 0xc3, 0xc5, 0xc7, 0xf2, 0xa0, 0xd0, 0xdf, 0xf8, 0xf4, + 0x19, 0xd1, 0xd8, 0xf2, 0xa0, 0xd0, 0xdf, 0xf1, 0xbc, 0xbc, 0xbc, 0xb1, 0xad, 0x8a, 0x9e, 0x26, + 0x46, 0x66, 0xbc, 0xb3, 0xf3, 0xa2, 0xde, 0xf8, 0xf4, 0x1a, 0x17, 0xd8, 0xf1, 0xaa, 0x8d, 0xc1, + 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0xaf, 0x8a, 0x9a, 0x21, 0x8f, + 0x90, 0xf5, 0x10, 0xda, 0xf4, 0x18, 0x5c, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x18, + 0xa3, 0xd8, 0xf3, 0xa1, 0xde, 0xf8, 0xa0, 0xdf, 0xf8, 0xf4, 0x19, 0xd1, 0xf3, 0x91, 0xfc, 0xc0, + 0x07, 0xd9, 0xf4, 0x18, 0xa3, 0xd8, 0xf1, 0xaf, 0xb1, 0x84, 0x9c, 0x01, 0xb3, 0xb5, 0x80, 0x97, + 0xdb, 0xf3, 0x21, 0xb9, 0xa7, 0xd9, 0xf8, 0xf4, 0x18, 0xa3, 0xd8, 0xf3, 0xb9, 0xa7, 0xde, 0xf8, + 0xbb, 0xf1, 0xa3, 0x87, 0xc0, 0xc3, 0xc5, 0xc7, 0xa4, 0x88, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x89, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xc4, 0xc7, 0xa1, 0x82, 0xc3, 0xc5, 0xc7, 0xf3, 0xa1, 0xde, + 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xbb, 0xb3, 0xb7, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, 0xa0, 0xd0, + 0xdf, 0xf8, 0xd8, 0xf1, 0xb9, 0xb1, 0xb6, 0xa8, 0x87, 0x90, 0x2d, 0x55, 0x7d, 0xf5, 0xb5, 0xa8, + 0x88, 0x98, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x86, 0x98, 0x29, 0xdb, 0x31, 0x39, 0xf4, 0x19, 0xe7, + 0xd8, 0xf1, 0xb3, 0xb6, 0xa7, 0x8a, 0x90, 0x4c, 0x54, 0x5c, 0xba, 0xa0, 0x81, 0x90, 0x2d, 0x55, + 0x7d, 0xbb, 0xf2, 0xa2, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xf4, 0x19, 0xe7, 0xd8, 0xf1, 0xba, 0xb0, + 0xab, 0x8f, 0xc0, 0xc7, 0xb3, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa2, 0x84, 0xc0, 0xc3, 0xc5, + /* bank # 25 */ + 0xc7, 0xa4, 0x85, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x86, 0xc0, 0xc3, 0xac, 0x8c, 0xc2, 0xf3, 0xae, + 0xde, 0xf8, 0xf8, 0xf4, 0x1a, 0x8e, 0xd8, 0xf1, 0xb2, 0xbb, 0xa3, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, + 0xa4, 0x82, 0xc0, 0xc3, 0xc5, 0xc7, 0xa5, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x85, 0xc0, 0xc3, + 0xac, 0x8c, 0xc4, 0xb3, 0xb7, 0xaf, 0x85, 0x95, 0x56, 0xfd, 0x0f, 0x86, 0x96, 0x06, 0xfd, 0x0f, + 0xf0, 0x84, 0x9f, 0xaf, 0x4c, 0x70, 0xfd, 0x0f, 0xf1, 0x86, 0x96, 0x2e, 0xfd, 0x0f, 0x84, 0x9f, + 0x72, 0xfd, 0x0f, 0xdf, 0xaf, 0x2c, 0x54, 0x7c, 0xaf, 0x8c, 0x69, 0xdb, 0x71, 0x79, 0x8b, 0x9c, + 0x61, 0xf4, 0x19, 0x67, 0xda, 0x19, 0xe7, 0xd8, 0xf1, 0xab, 0x83, 0x91, 0x28, 0xfd, 0x05, 0x54, + 0xfd, 0x05, 0x7c, 0xfd, 0x05, 0xb8, 0xbd, 0xbd, 0xbd, 0xb5, 0xa3, 0x8b, 0x95, 0x05, 0x2d, 0x55, + 0xbd, 0xb4, 0xbb, 0xad, 0x8e, 0x93, 0x0e, 0x16, 0x1e, 0xb7, 0xf3, 0xa2, 0xde, 0xf8, 0xf8, 0xf4, + 0x1a, 0x17, 0xd8, 0xf2, 0xa1, 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xaf, 0x8d, 0x9a, 0x01, 0xf5, 0x8f, + 0x90, 0xdb, 0x00, 0xf4, 0x19, 0xe7, 0xda, 0xf1, 0xaa, 0x8d, 0xc0, 0xae, 0x8b, 0xc1, 0xc3, 0xc5, + 0xa1, 0xde, 0xa7, 0x83, 0xc0, 0xc3, 0xc5, 0xc7, 0xa8, 0x84, 0xc0, 0xc3, 0xc5, 0xc7, 0xa9, 0x85, + 0xc0, 0xc3, 0xc5, 0xc7, 0xa6, 0x86, 0xd0, 0xc0, 0xc3, 0xa2, 0x81, 0xc3, 0xc5, 0xc7, 0xf4, 0x19, + 0xe7, 0xf1, 0xbb, 0xb3, 0xa3, 0xde, 0xdf, 0xdf, 0xdf, 0xa4, 0x8c, 0xc4, 0xc5, 0xc5, 0xc5, 0xa5, + 0xde, 0xdf, 0xdf, 0xdf, 0xa6, 0xde, 0xdf, 0xd8, 0xf3, 0xb9, 0xae, 0xdf, 0xba, 0xae, 0xde, 0xbb, + 0xa2, 0xde, 0xbe, 0xbc, 0xb3, 0xbd, 0xb7, 0xaf, 0x8e, 0x9c, 0x01, 0xd1, 0xac, 0xc0, 0xd9, 0xae, + /* bank # 26 */ + 0xde, 0xd8, 0xf1, 0xb1, 0x83, 0xb9, 0xa7, 0xd0, 0xc4, 0xb8, 0xae, 0xde, 0xbe, 0xbe, 0xbe, 0xbb, + 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xd8, 0xf3, 0xa2, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1a, + 0x8c, 0xd8, 0xf5, 0xad, 0x8d, 0x9d, 0x2c, 0x54, 0x7c, 0xf1, 0xaf, 0x49, 0xda, 0xc3, 0xc5, 0xd9, + 0xc5, 0xc3, 0xd8, 0xaf, 0x9f, 0x69, 0xd0, 0xda, 0xc7, 0xd9, 0x8f, 0xc3, 0x8d, 0xaf, 0xc7, 0xd8, + 0xb9, 0xa9, 0x8f, 0x9f, 0xf0, 0x54, 0x78, 0xf1, 0xfd, 0x0f, 0xa6, 0xb1, 0x89, 0xc2, 0xb3, 0xaf, + 0x8f, 0x9f, 0x2e, 0xfd, 0x11, 0xb1, 0xb5, 0xa9, 0x89, 0x9f, 0x2c, 0xf3, 0xae, 0xdf, 0xf8, 0xf8, + 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xad, 0x86, 0x99, 0x06, 0xfd, 0x10, 0xdf, 0xf8, 0xfd, 0x0f, 0xad, + 0x8d, 0x9d, 0x4c, 0xbb, 0xb3, 0xad, 0x8f, 0x9d, 0x2a, 0xfd, 0x0f, 0xb7, 0x92, 0xfc, 0xc0, 0x04, + 0xd9, 0xf4, 0x18, 0x2b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, 0x92, 0xd8, 0xf1, 0xd8, 0xf3, + 0xba, 0xb2, 0xb6, 0xae, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, 0x1c, 0x41, 0xd8, 0xf1, 0xaf, 0xde, 0xf9, + 0xfd, 0x0f, 0x80, 0x90, 0x2c, 0x54, 0x7c, 0xa0, 0x2a, 0xf0, 0x50, 0x78, 0xfd, 0x0f, 0xf1, 0xa2, + 0x82, 0x9c, 0x00, 0x24, 0x44, 0x64, 0xa9, 0x8f, 0x94, 0xf0, 0x04, 0xfd, 0x0f, 0x0c, 0x30, 0xfd, + 0x0f, 0x1c, 0x95, 0x20, 0x48, 0xfd, 0x0f, 0xf1, 0x99, 0xc1, 0x2c, 0x54, 0x7c, 0xaa, 0x82, 0x99, + 0x02, 0xfd, 0x0f, 0x2e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0x7e, 0xfd, 0x0f, 0xac, 0x83, 0x9f, 0xf0, + 0x04, 0x28, 0x50, 0x78, 0xfd, 0x0f, 0x8c, 0x90, 0xf1, 0x21, 0xf5, 0x8c, 0x9c, 0x2c, 0xf1, 0xaf, + 0xde, 0xf1, 0x89, 0xaf, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, 0xc1, 0x8a, 0xc1, 0x82, 0xc1, 0xd8, 0xfc, + /* bank # 27 */ + 0xc0, 0x04, 0xd9, 0xc3, 0x8a, 0xc3, 0x82, 0xc3, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xc5, 0x8a, 0xc5, + 0x82, 0xc5, 0xd8, 0xfc, 0xc0, 0x0c, 0xd9, 0xc7, 0x8a, 0xc7, 0x82, 0xc7, 0xd8, 0xfc, 0xc0, 0x10, + 0xd9, 0xf4, 0x1b, 0xfb, 0xd8, 0xf1, 0x8b, 0xab, 0xd0, 0xc0, 0x9f, 0x2e, 0xfd, 0x0f, 0xa0, 0xde, + 0xab, 0xd0, 0x90, 0x65, 0xa0, 0x8f, 0x9f, 0x4a, 0xfd, 0x0f, 0xab, 0x8b, 0x90, 0x00, 0xb9, 0xa9, + 0xc1, 0xf3, 0xae, 0xdf, 0xf8, 0xf4, 0x1c, 0x43, 0xd8, 0xf1, 0xba, 0xb1, 0xb6, 0x89, 0xab, 0xc1, + 0xb2, 0xaf, 0xd0, 0x8b, 0x9f, 0x3e, 0xfd, 0x0f, 0x5a, 0xfd, 0x0f, 0x9f, 0xfc, 0xc0, 0x00, 0xd9, + 0xf1, 0x8f, 0xa2, 0xc6, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x8f, 0xa2, 0xc7, 0x84, 0xab, 0xd0, 0xc0, + 0xaf, 0x8a, 0x9b, 0x1e, 0xfd, 0x0f, 0x36, 0xfd, 0x0f, 0xa4, 0x8f, 0x30, 0xaa, 0x9a, 0x40, 0xd8, + 0x9f, 0xfc, 0xc0, 0x08, 0xd9, 0x8f, 0xa2, 0xd0, 0xc6, 0x84, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, + 0x1e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x84, 0xab, 0xd0, 0xc4, + 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x56, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x30, 0xaa, 0x9a, 0x4c, + 0xd8, 0x9f, 0xfc, 0xc0, 0x0c, 0xd9, 0x8f, 0xa2, 0xd0, 0xc7, 0x84, 0xab, 0xd0, 0xc6, 0xaf, 0x8a, + 0x9b, 0x1e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa4, 0xd0, 0x8f, 0x34, 0xaa, 0x9a, 0x40, 0x85, 0xab, + 0xd0, 0xc0, 0xaf, 0x8a, 0x9b, 0x3e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, 0x30, 0xaa, 0x9a, + 0x4c, 0x85, 0xab, 0xd0, 0xc2, 0xaf, 0x8a, 0x9b, 0x5e, 0xfd, 0x0f, 0x76, 0xfd, 0x0f, 0xa5, 0x8f, + 0x34, 0xaa, 0xd0, 0x9a, 0x50, 0xd8, 0xaf, 0xf8, 0xf4, 0x1a, 0xf1, 0xf1, 0xd8, 0x8b, 0x9c, 0xaf, + /* bank # 28 */ + 0x2a, 0xfd, 0x0f, 0x8a, 0x9f, 0xb9, 0xaf, 0x02, 0xfd, 0x0f, 0x26, 0xfd, 0x0f, 0x46, 0xfd, 0x0f, + 0x66, 0xfd, 0x0f, 0x83, 0xb5, 0x9f, 0xba, 0xa3, 0x00, 0x2c, 0x54, 0x7c, 0xb6, 0x82, 0x92, 0xa0, + 0x31, 0xd9, 0xad, 0xc3, 0xda, 0xad, 0xc5, 0xd8, 0x8d, 0xa0, 0x39, 0xda, 0x82, 0xad, 0xc7, 0xd8, + 0xf3, 0x9e, 0xfc, 0xc0, 0x04, 0xd9, 0xf4, 0x17, 0x1b, 0xd8, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x19, + 0x16, 0xd8, 0xf1, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa9, 0xde, 0xf8, 0x89, 0x99, 0xaf, 0x31, 0xd9, + 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x85, 0xaf, 0x29, 0xd9, 0x84, 0xa9, 0xc2, 0xd8, 0x85, 0xaf, 0x49, + 0xd9, 0x84, 0xa9, 0xc4, 0xd8, 0x85, 0xaf, 0x69, 0xd9, 0x84, 0xa9, 0xc6, 0xd8, 0x89, 0xaf, 0x39, + 0xda, 0x8e, 0xa9, 0x50, 0xf4, 0x1c, 0x97, 0xd8, 0xf1, 0x89, 0xaa, 0x7c, 0xfd, 0x02, 0x9a, 0x68, + 0xd8, 0xf1, 0xaa, 0xfb, 0xda, 0x89, 0x99, 0xaf, 0x26, 0xfd, 0x0f, 0x8f, 0x95, 0x25, 0x89, 0x9f, + 0xa9, 0x12, 0xfd, 0x0f, 0xf4, 0x1c, 0x80, 0xd8, 0xf3, 0x9e, 0xfc, 0xc1, 0x04, 0xd9, 0xf4, 0x1b, + 0x48, 0xd8, 0xfc, 0xc1, 0x08, 0xd9, 0xf4, 0x1a, 0x63, 0xd8, 0xf1, 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, + 0xf3, 0xb8, 0xb4, 0xb0, 0x8f, 0xa8, 0xc0, 0xf9, 0xac, 0x84, 0x97, 0xf5, 0x1a, 0xf1, 0xf8, 0xf9, + 0xd1, 0xda, 0xa8, 0xde, 0xd8, 0x95, 0xfc, 0xc1, 0x03, 0xd9, 0xa8, 0xde, 0xd8, 0xbc, 0xbc, 0xf1, + 0x98, 0xfc, 0xc0, 0x1c, 0xdb, 0x95, 0xfc, 0xc0, 0x03, 0xa5, 0xde, 0xa4, 0xde, 0xd8, 0xac, 0x88, + 0x95, 0x00, 0xd1, 0xd9, 0xa5, 0xf8, 0xd8, 0xa4, 0xfc, 0x80, 0x04, 0x88, 0x95, 0xa4, 0xfc, 0x08, + 0x04, 0x20, 0xf7, 0xbc, 0xbc, 0xbd, 0xbd, 0xb5, 0xac, 0x84, 0x9f, 0xf6, 0x02, 0xf8, 0xf9, 0xd1, + /* bank # 29 */ + 0xdb, 0x84, 0x93, 0xf7, 0x6a, 0xf9, 0xd9, 0xf3, 0xbc, 0xbc, 0xa8, 0x88, 0x92, 0x18, 0xbc, 0xbc, + 0xd8, 0xbc, 0xbc, 0xb4, 0xa8, 0x88, 0x9e, 0x08, 0xf4, 0xbe, 0xbe, 0xa1, 0xd0, 0xbc, 0xbc, 0xf7, + 0xbe, 0xbe, 0xb5, 0xac, 0x84, 0x93, 0x6a, 0xf9, 0xbd, 0xbd, 0xb4, 0xd9, 0xf2, 0xac, 0x8c, 0x97, + 0x18, 0xf6, 0x84, 0x9c, 0x02, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0xa5, 0xdf, 0xd8, 0xf7, 0xbe, 0xbe, + 0xbd, 0xbd, 0xa7, 0x9d, 0x88, 0x7a, 0xf9, 0xd9, 0xf4, 0x1e, 0xe1, 0xd8, 0xf1, 0xbe, 0xbe, 0xac, + 0xde, 0xdf, 0xac, 0x88, 0x9f, 0xf7, 0x5a, 0x56, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0x95, 0xfc, 0xc0, + 0x07, 0xda, 0xf4, 0x1e, 0x7c, 0xd8, 0xf1, 0xfc, 0xc0, 0x00, 0xdb, 0x9c, 0xfc, 0xc1, 0x00, 0xf4, + 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x95, 0xfc, 0xc0, 0x08, 0xda, 0xf4, 0x1d, 0xbe, 0xd8, 0xf1, 0x82, + 0x90, 0x79, 0x2d, 0x55, 0xf5, 0x8c, 0x9c, 0x04, 0xac, 0x2c, 0x54, 0xf1, 0xbc, 0xbc, 0xbc, 0x80, + 0x5d, 0xdb, 0x49, 0x51, 0xf4, 0xbc, 0x1d, 0x9c, 0xda, 0xbc, 0x1e, 0x78, 0xd8, 0xf5, 0x86, 0x98, + 0x38, 0xd9, 0xf1, 0x82, 0x90, 0x2d, 0xd8, 0xac, 0xd0, 0x86, 0x98, 0xf5, 0x5c, 0xd9, 0xf1, 0x82, + 0x90, 0x55, 0xd8, 0xac, 0x8c, 0x9c, 0x00, 0x00, 0xa5, 0xdf, 0xf8, 0xf4, 0x1d, 0xc9, 0xd8, 0xf1, + 0x82, 0x96, 0x2d, 0x55, 0x7d, 0x8c, 0x9c, 0x34, 0x18, 0xf1, 0xac, 0x95, 0xf5, 0x1c, 0xd9, 0xf4, + 0x1e, 0x78, 0xd8, 0xf1, 0xac, 0x83, 0x90, 0x45, 0xd9, 0xa0, 0xf8, 0xac, 0x8c, 0x9c, 0x06, 0xd2, + 0xa1, 0x91, 0x00, 0x2c, 0x81, 0xd6, 0xf0, 0xa1, 0xd0, 0x8c, 0x9c, 0x28, 0xd3, 0x87, 0xd4, 0xa7, + 0x8c, 0x20, 0xd3, 0xf1, 0xa4, 0x84, 0x90, 0x2c, 0x54, 0x7c, 0xd8, 0xac, 0x83, 0x90, 0x45, 0xd9, + /* bank # 30 */ + 0xf4, 0x1e, 0xa1, 0xd8, 0xf1, 0xac, 0x81, 0x91, 0x02, 0xfd, 0x14, 0x85, 0x66, 0xfd, 0x1d, 0x88, + 0x4e, 0xfd, 0x1b, 0x87, 0xd4, 0xfd, 0x54, 0xad, 0x8d, 0x4e, 0xf0, 0x81, 0x9c, 0xab, 0xd6, 0xfd, + 0x06, 0x8d, 0x31, 0x8c, 0x10, 0x10, 0x01, 0x01, 0x01, 0x39, 0xac, 0x8b, 0x98, 0xf5, 0x08, 0xd9, + 0xf4, 0x1e, 0x78, 0xd8, 0xf1, 0xa9, 0x82, 0x96, 0x01, 0x95, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x1e, + 0x50, 0xdb, 0xf1, 0xac, 0x89, 0x93, 0xf5, 0x18, 0xf1, 0xa5, 0xdf, 0xf8, 0xd8, 0xf4, 0x1e, 0x7c, + 0xd8, 0xf1, 0xa4, 0x84, 0x95, 0x34, 0xfd, 0x05, 0x54, 0xfd, 0x05, 0x74, 0xfd, 0x05, 0xa9, 0x94, + 0xf5, 0x2c, 0x54, 0x7c, 0xf1, 0xac, 0x87, 0x99, 0x49, 0xdb, 0x51, 0x59, 0x84, 0xab, 0xc3, 0xc5, + 0xc7, 0x82, 0xa6, 0xc0, 0xf3, 0xaa, 0xdf, 0xf8, 0xd8, 0xf1, 0xa5, 0xdf, 0xd8, 0xf1, 0xa0, 0xde, + 0xa1, 0xde, 0xdf, 0xdf, 0xdf, 0xa7, 0xde, 0xdf, 0xa4, 0xdf, 0xdf, 0xdf, 0xa2, 0x95, 0xfc, 0xc0, + 0x01, 0xd9, 0x80, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, 0xc1, 0xda, 0x86, 0xc3, 0xc5, 0xc7, 0xa8, 0x83, + 0xc3, 0xd8, 0xf1, 0x9a, 0xfc, 0xc1, 0x04, 0xd9, 0xac, 0x82, 0x96, 0x01, 0xf3, 0xaa, 0xde, 0xf8, + 0xf8, 0xf8, 0xdb, 0xf5, 0xac, 0x8c, 0x9a, 0x18, 0xf3, 0xaa, 0xf9, 0xd8, 0xac, 0x8a, 0x9a, 0x41, + 0xd1, 0xaa, 0xd0, 0xc0, 0xd9, 0xf2, 0xac, 0x85, 0x9a, 0x41, 0xdb, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xf4, 0x1e, 0xe1, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xa5, 0x85, 0x9c, + 0x10, 0xd8, 0xf1, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, 0x9e, 0xf7, 0x7a, 0xf9, 0xd9, 0xf4, 0x20, 0x18, + 0xd8, 0xf1, 0xbe, 0xbe, 0xbe, 0xbb, 0xa2, 0xf9, 0xda, 0xbe, 0xf4, 0x20, 0x18, 0xd8, 0xf1, 0xbc, + /* bank # 31 */ + 0xbc, 0xbc, 0xb3, 0x80, 0xc6, 0xaf, 0xde, 0xd0, 0xdf, 0xbc, 0xb2, 0x84, 0xbd, 0xbd, 0xbd, 0xb7, + 0x9f, 0xa0, 0x60, 0xbc, 0xbc, 0xbc, 0xb3, 0x85, 0x90, 0xaf, 0x01, 0x9f, 0x46, 0x8f, 0xa2, 0x0e, + 0x85, 0x92, 0xaf, 0xd0, 0x29, 0x9f, 0x52, 0xa5, 0x08, 0x34, 0xa0, 0xfb, 0x86, 0x95, 0xaf, 0x29, + 0xda, 0xa6, 0xde, 0xf4, 0x1f, 0x4c, 0xd8, 0xf1, 0xa0, 0xfa, 0xf9, 0xda, 0xa6, 0xde, 0xf4, 0x1f, + 0x4c, 0xd8, 0xf1, 0xa6, 0xf8, 0x96, 0xaf, 0x19, 0xd9, 0xa3, 0xde, 0xf8, 0xd8, 0xf1, 0x85, 0x94, + 0xaf, 0x31, 0xd9, 0xa3, 0xde, 0xf8, 0xf8, 0x80, 0xa0, 0xc5, 0xd8, 0x85, 0x96, 0xaf, 0x31, 0xd9, + 0xa3, 0xde, 0xf8, 0xf8, 0xf8, 0x80, 0xa5, 0xc0, 0x86, 0xc3, 0xd8, 0xa8, 0xdf, 0xa1, 0xde, 0x85, + 0x91, 0xaf, 0x0c, 0x0d, 0xf5, 0x8f, 0x9f, 0xaf, 0x2c, 0x54, 0xf1, 0x97, 0xfc, 0xc0, 0x04, 0xdb, + 0x8f, 0xaf, 0x51, 0xa8, 0xdf, 0xf8, 0xd8, 0x98, 0xfc, 0xc0, 0x08, 0xd9, 0xf4, 0x1f, 0xb4, 0xd8, + 0xf1, 0xfc, 0xc0, 0x0c, 0xd9, 0xf4, 0x1f, 0xdd, 0xd8, 0xf1, 0x93, 0xfc, 0xc0, 0x09, 0xd9, 0xa4, + 0xde, 0xa8, 0xde, 0xf8, 0xf8, 0xd8, 0xfc, 0xc0, 0x04, 0xd9, 0x85, 0xa1, 0xc1, 0xa7, 0xde, 0xf8, + 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, 0xf8, 0x82, 0x91, 0xaf, 0x31, 0xdb, 0x9f, 0x71, 0x92, + 0x41, 0xa7, 0xde, 0xd8, 0x84, 0x94, 0xaf, 0x19, 0xd9, 0xa8, 0xde, 0xf8, 0xf8, 0xf8, 0xa3, 0xdf, + 0xd8, 0x93, 0xfc, 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf4, 0x1f, 0xf6, 0xd8, 0xf1, 0xa4, + 0xf8, 0xa3, 0xfa, 0xf9, 0xd1, 0xdb, 0x88, 0x94, 0xaf, 0x41, 0x88, 0xa1, 0xc2, 0xd8, 0x93, 0xfc, + 0xc0, 0x0a, 0xd9, 0xa8, 0xde, 0xf8, 0xd8, 0xf1, 0x91, 0xfc, 0xc0, 0x04, 0xd9, 0xa7, 0xfa, 0xa3, + /* bank # 32 */ + 0xfa, 0xaf, 0xd0, 0xdf, 0xf8, 0xf8, 0xd8, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xb0, 0xbc, 0xb4, 0xbd, + 0xb8, 0xbe, 0xda, 0xf3, 0xa5, 0x85, 0x9d, 0x08, 0xd8, 0xf1, 0xf1, 0xa7, 0xde, 0xf7, 0x84, 0x9f, + 0x6a, 0x87, 0xf1, 0xd4, 0xfd, 0x3e, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf0, 0xf7, 0xa7, 0x88, + 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x20, 0x48, 0xd8, 0xf2, 0xbb, 0xa0, 0xf9, 0xda, 0xf4, 0x20, 0x48, + 0xd8, 0xf2, 0xb3, 0x80, 0xc4, 0xf4, 0x75, 0xdc, 0xd8, 0xf0, 0xb1, 0xb5, 0xba, 0x8a, 0x9a, 0xa7, + 0xf0, 0x2c, 0x50, 0x78, 0xf2, 0xa5, 0xde, 0xf8, 0xf8, 0xf1, 0xb5, 0xb2, 0xa7, 0x87, 0x90, 0x21, + 0xdb, 0xb6, 0xb1, 0x80, 0x97, 0x29, 0xd9, 0xf2, 0xa5, 0xf8, 0xd8, 0xbb, 0xb2, 0xb6, 0xbe, 0xa1, + 0xf8, 0xf9, 0xd1, 0xbe, 0xbe, 0xbe, 0xba, 0xda, 0xa5, 0xde, 0xd8, 0xa7, 0x82, 0x95, 0x65, 0xd1, + 0x85, 0xa2, 0xd0, 0xc1, 0xd9, 0xb5, 0xa7, 0x86, 0x93, 0x31, 0xdb, 0xd1, 0xf4, 0x20, 0x98, 0xd8, + 0xf3, 0xb8, 0xb0, 0xb4, 0xa5, 0x85, 0x9c, 0x18, 0xd8, 0xf1, 0xba, 0xb2, 0xb6, 0x81, 0x96, 0xa1, + 0xf8, 0xf9, 0xb9, 0xa6, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x8a, 0xaa, + 0xf8, 0xf9, 0xb9, 0xae, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xba, 0x88, 0xa8, + 0xf8, 0xf9, 0xa7, 0xda, 0xc3, 0xc5, 0xc7, 0xd9, 0x2d, 0x4d, 0x6d, 0xd8, 0xf2, 0xb0, 0xb9, 0xa3, + 0xfa, 0xf9, 0xd1, 0xda, 0xb8, 0x8f, 0xa7, 0xc0, 0xf9, 0xb5, 0x87, 0x93, 0xf6, 0x0a, 0xf2, 0xb4, + 0xa4, 0x84, 0x97, 0x24, 0xa4, 0x84, 0x9e, 0x3c, 0xd8, 0xf3, 0xbe, 0xbe, 0xbb, 0xae, 0xf8, 0xf9, + 0xd1, 0xbe, 0xbe, 0xb0, 0xb4, 0xb8, 0xda, 0xa5, 0x85, 0x9e, 0x00, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + /* bank # 33 */ + 0xbd, 0x8e, 0x9e, 0xa7, 0x59, 0xd1, 0xbc, 0xbc, 0xbd, 0xbd, 0xda, 0x85, 0x9e, 0xa5, 0x08, 0xd8, + 0xf1, 0xbc, 0xbc, 0x8e, 0xbe, 0xbe, 0xae, 0xd0, 0xc5, 0xbc, 0xbc, 0xbe, 0xbe, 0xf7, 0xb9, 0xb0, + 0xb5, 0xa6, 0x88, 0x95, 0x5a, 0xf9, 0xda, 0xf1, 0xab, 0xf8, 0xd8, 0xb8, 0xb4, 0xf3, 0x98, 0xfc, + 0xc0, 0x04, 0xda, 0xf4, 0x21, 0x86, 0xd8, 0xf2, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, + 0xa9, 0xd0, 0xde, 0xa4, 0x84, 0x9e, 0x2c, 0xd8, 0xa8, 0xfa, 0x88, 0x9a, 0xa7, 0x29, 0xd9, 0xa8, + 0xdf, 0xa4, 0x84, 0x9d, 0x34, 0xd8, 0xa8, 0xd0, 0xf8, 0x88, 0x9a, 0xa7, 0x51, 0xd9, 0xa8, 0xd0, + 0xde, 0xa4, 0x84, 0x9d, 0x2c, 0xd8, 0xa8, 0xd0, 0xfa, 0x88, 0x9a, 0xa7, 0x79, 0xd9, 0xa8, 0xd0, + 0xdf, 0xa4, 0x84, 0x9d, 0x24, 0xd8, 0xf3, 0xa9, 0xd0, 0xf8, 0x89, 0x9b, 0xa7, 0x51, 0xd9, 0xa9, + 0xd0, 0xde, 0xa4, 0x84, 0x9c, 0x2c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x52, 0xf9, 0xd9, 0xf4, 0x21, + 0xb6, 0xd8, 0xf1, 0xb9, 0xa2, 0xfa, 0xf3, 0xb8, 0xa9, 0xd0, 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, + 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9c, 0x24, 0xd8, 0xf2, 0xa8, 0xf8, 0x88, 0x9a, 0xa7, 0x01, 0xd9, + 0xa8, 0xde, 0xa4, 0x84, 0x9d, 0x3c, 0xd8, 0xf7, 0xa7, 0x88, 0x9f, 0x42, 0xf9, 0xd9, 0xf4, 0x21, + 0xfd, 0xd8, 0xf3, 0xa9, 0xf8, 0x89, 0x9b, 0xa7, 0x01, 0xd9, 0xa9, 0xde, 0xa4, 0x84, 0x9c, 0x3c, + 0xd8, 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9c, 0x34, 0xd8, 0xf2, + 0xa9, 0xfa, 0x89, 0x9b, 0xa7, 0x29, 0xd9, 0xa9, 0xdf, 0xa4, 0x84, 0x9e, 0x34, 0xd8, 0xa9, 0xd0, + 0xfa, 0x89, 0x9b, 0xa7, 0x79, 0xd9, 0xa9, 0xd0, 0xdf, 0xa4, 0x84, 0x9e, 0x24, 0xd8, 0xf1, 0xa7, + /* bank # 34 */ + 0xde, 0xf2, 0x84, 0xca, 0x97, 0xa4, 0x24, 0xa5, 0x94, 0xf6, 0x0a, 0xf7, 0x85, 0x02, 0xf8, 0xf9, + 0xd1, 0xd9, 0xf6, 0x9b, 0x02, 0xd8, 0xa7, 0xb1, 0x82, 0x95, 0x62, 0xf8, 0xf9, 0xd1, 0xd9, 0xf4, + 0x23, 0xf2, 0xd8, 0xf0, 0xb0, 0x85, 0xa4, 0xd0, 0xc0, 0xdd, 0xf2, 0xc0, 0xdc, 0xf6, 0xa7, 0x9f, + 0x02, 0xf9, 0xd9, 0xf3, 0xa5, 0xde, 0xda, 0xf0, 0xdd, 0xf2, 0xc8, 0xdc, 0xd8, 0x85, 0x95, 0xa5, + 0x00, 0xd9, 0x86, 0xf0, 0xdd, 0xf2, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0x80, 0xf0, + 0xdd, 0xf2, 0xcc, 0xc6, 0xce, 0x85, 0xca, 0xcc, 0xce, 0xdc, 0xd8, 0x85, 0x00, 0xd9, 0xb1, 0x89, + 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x81, 0xf0, 0xdd, 0xf2, + 0xc6, 0xce, 0x82, 0xc0, 0xc8, 0xdc, 0xd8, 0x85, 0x00, 0xb1, 0xd9, 0x86, 0xf0, 0xdd, 0xf1, 0xc2, + 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, 0x00, 0xd9, 0xb2, 0x87, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, + 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, 0x85, 0x00, 0xb1, 0xd9, + 0x8f, 0xf0, 0xdd, 0xf2, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0xb1, 0x8e, 0xf0, + 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xf2, 0xbc, 0xb0, 0x81, 0xc0, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, 0xb0, + 0x85, 0x00, 0xd9, 0x82, 0xf0, 0xdd, 0xf2, 0xc2, 0xca, 0xc4, 0xdc, 0xd8, 0x85, 0x00, 0xd8, 0xf2, + 0x85, 0x00, 0xd9, 0xb1, 0x8a, 0xf0, 0xdd, 0xf1, 0xc2, 0xc4, 0xc6, 0xdc, 0xd8, 0xb0, 0xf2, 0x85, + 0x00, 0xd9, 0xb1, 0xf0, 0xdd, 0xf1, 0x82, 0xc4, 0xdc, 0xd8, 0xb0, 0xf3, 0xa5, 0xf8, 0xf9, 0xd1, + 0xd9, 0xf4, 0x23, 0x74, 0xd8, 0xf3, 0x85, 0x95, 0xa5, 0x00, 0x00, 0xd9, 0xbe, 0xf2, 0xba, 0xae, + /* bank # 35 */ + 0xde, 0xbe, 0xbe, 0xbe, 0xbc, 0xb2, 0x81, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xbc, 0xbc, 0xbc, 0xd8, + 0xb0, 0xb8, 0x85, 0xa5, 0x00, 0xd9, 0xf2, 0xbe, 0xbe, 0xaa, 0xde, 0xbe, 0xbe, 0xbc, 0xbc, 0x8a, + 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xbc, 0xbc, 0xd8, 0x85, 0xa5, 0x00, 0xd9, 0xb9, 0xf2, 0xa3, 0xd0, + 0xde, 0xb2, 0x85, 0xf0, 0xdd, 0xf3, 0xc8, 0xdc, 0xd8, 0xb0, 0x85, 0xb8, 0xa5, 0x00, 0xd9, 0xb3, + 0x8a, 0xf0, 0xdd, 0xf3, 0xc0, 0xdc, 0xd8, 0xb0, 0x85, 0x00, 0xd9, 0x8f, 0xf0, 0xdd, 0xf3, 0xc4, + 0xdc, 0xd8, 0x85, 0x00, 0x00, 0x00, 0xd9, 0xbc, 0xbc, 0xb3, 0x8e, 0xf0, 0xdd, 0xf3, 0xc0, 0xf1, + 0xc2, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x85, 0x00, 0xd9, 0xbc, 0xbc, 0x8e, 0xf0, 0xdd, 0xf3, + 0xc4, 0xdc, 0xbc, 0xbc, 0xd8, 0xf3, 0xb0, 0x8e, 0xf4, 0xb8, 0xa7, 0xd0, 0xc0, 0xd8, 0x87, 0xf3, + 0xb9, 0xa2, 0xc6, 0xa6, 0xc4, 0xf7, 0xb5, 0x8e, 0x96, 0x06, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x23, + 0x7d, 0xd8, 0xf3, 0x8e, 0xc0, 0xf9, 0xb1, 0x86, 0x96, 0xf7, 0x0a, 0xdf, 0xf3, 0x30, 0xfd, 0x08, + 0xa2, 0x82, 0x10, 0xf0, 0xdd, 0xf3, 0x82, 0xc0, 0xdc, 0xf2, 0xb9, 0xa3, 0xdf, 0xf4, 0xb1, 0x8c, + 0xf3, 0xaf, 0xc1, 0xc3, 0xaf, 0x8f, 0xb4, 0x9d, 0x3e, 0xfd, 0x1e, 0xb5, 0x9f, 0x30, 0xa6, 0x39, + 0xd9, 0xf4, 0x23, 0xec, 0xd8, 0xf7, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x9d, 0x1a, 0xf9, 0xd9, 0xf4, + 0x23, 0xdf, 0xd8, 0xf1, 0xb9, 0xb1, 0xb5, 0xa6, 0x83, 0x9b, 0x61, 0xd9, 0xf4, 0x23, 0xf2, 0xd8, + 0xf6, 0xb8, 0xb0, 0xb4, 0xa7, 0x84, 0x94, 0x5a, 0xf8, 0xf9, 0xd1, 0xda, 0xf0, 0xe2, 0xf1, 0xb9, + 0xab, 0xde, 0xd8, 0xf2, 0xb1, 0x86, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xb8, 0xb0, 0xb4, 0xa7, 0x88, + /* bank # 36 */ + 0x9c, 0xf7, 0x6a, 0xf9, 0xd9, 0xff, 0xd8, 0x72, 0xb9, 0xab, 0xf1, 0xdf, 0xf7, 0x62, 0xf3, 0xf8, + 0xf9, 0xd1, 0xda, 0xf1, 0xde, 0xf8, 0xd8, 0xf7, 0xbb, 0xaf, 0x7a, 0x9d, 0x66, 0x9e, 0x76, 0x9f, + 0x76, 0xf1, 0xa1, 0xdf, 0xba, 0xa6, 0xd0, 0xde, 0xbb, 0xf3, 0xa0, 0xf9, 0xda, 0xff, 0xd8, 0xb3, + 0x80, 0xc4, 0xaf, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xbc, 0xbc, 0xbc, 0xf4, 0x25, 0xba, 0xd8, 0xf1, + 0xb8, 0xbe, 0xbe, 0xae, 0xd0, 0xde, 0xb0, 0x84, 0xba, 0xbe, 0xa7, 0xc1, 0xf7, 0x88, 0xb4, 0x9d, + 0x6e, 0xf9, 0xb2, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xda, 0xf4, 0x24, 0x8f, 0xd8, 0xf1, 0xb8, + 0xbe, 0xbe, 0xbe, 0xae, 0xd0, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xd9, + 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, + 0xd9, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xba, 0xbe, 0xf4, 0x24, 0xf6, 0xd8, + 0xf1, 0x91, 0xfc, 0xc0, 0x00, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x04, 0xf5, 0x87, 0x95, 0xa7, 0x3a, + 0xf1, 0xf9, 0xd9, 0xaf, 0xde, 0x8f, 0xbe, 0xbe, 0xa1, 0xf4, 0xc1, 0xf1, 0xa2, 0xf4, 0xc1, 0xf1, + 0xbe, 0xbe, 0xd8, 0xb4, 0x91, 0xfc, 0xc0, 0x04, 0xdb, 0xb6, 0x95, 0xfc, 0xc1, 0x00, 0xd9, 0xaf, + 0xde, 0xf8, 0xfd, 0x07, 0x8f, 0x95, 0x10, 0xdf, 0xf8, 0xf8, 0xf8, 0xa7, 0xde, 0xf8, 0xfd, 0x07, + 0xdf, 0xf8, 0xfd, 0x06, 0xdf, 0xf8, 0xfd, 0x04, 0x8f, 0x97, 0xaf, 0xd0, 0xde, 0x40, 0x48, 0x50, + 0xdf, 0xf8, 0x60, 0x8f, 0xbe, 0xbe, 0xa0, 0xd0, 0xf4, 0xc1, 0xf1, 0xa1, 0xf4, 0xc2, 0xc5, 0xf1, + 0xa2, 0xf4, 0xc7, 0xf1, 0xbe, 0xbe, 0xd8, 0xf1, 0xb0, 0x81, 0xa5, 0xc1, 0xbc, 0x84, 0xb8, 0xbe, + /* bank # 37 */ + 0xbe, 0xa9, 0xc1, 0xf7, 0x88, 0xb4, 0xbd, 0x9d, 0x6e, 0xf9, 0xbc, 0xbd, 0xda, 0xf4, 0x25, 0x43, + 0xd8, 0xf1, 0xa9, 0xde, 0xf8, 0xfd, 0x04, 0xdf, 0xf8, 0xfd, 0x05, 0xbc, 0x8e, 0xbe, 0xae, 0xd0, + 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xd9, 0x99, 0x40, 0xd8, 0x9a, 0xfc, 0xc0, + 0x04, 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0x99, 0x48, 0xd8, 0xbc, 0xbc, 0xbc, 0xbe, 0xbe, 0xbe, + 0xf4, 0x25, 0xad, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x00, 0xdb, 0x9b, 0xfc, 0xc0, 0x04, 0xf5, 0x89, + 0xa9, 0x32, 0xf9, 0xd9, 0xf1, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, 0xf8, 0xfd, + 0x07, 0xf8, 0xdf, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, + 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xa3, 0xf4, 0xc7, 0xf1, 0xb8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, + 0xdb, 0x9b, 0xfc, 0xc0, 0x00, 0xd9, 0xa9, 0xde, 0xf8, 0xfd, 0x02, 0xdf, 0xf8, 0xfd, 0x07, 0xdf, + 0xf8, 0xfd, 0x07, 0xf8, 0xdf, 0xf8, 0xfd, 0x04, 0xf9, 0x89, 0xba, 0xa0, 0xf4, 0xc0, 0xf1, 0x8b, + 0xa1, 0xd0, 0xf4, 0xc3, 0xf1, 0x89, 0xa2, 0xf4, 0xc2, 0xc5, 0xc7, 0xf1, 0xb8, 0xd8, 0xf1, 0x8a, + 0xab, 0xc0, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb2, 0x80, 0xba, 0xa7, + 0xc4, 0xbc, 0xb2, 0x8b, 0xf4, 0x75, 0x75, 0x8f, 0xb6, 0x9c, 0xf4, 0x75, 0x81, 0xaf, 0xf4, 0x75, + 0x87, 0x8b, 0xf4, 0x75, 0x75, 0x8e, 0xb6, 0x9d, 0xf4, 0x75, 0x81, 0xae, 0xf4, 0x75, 0x87, 0xb3, + 0x81, 0xf4, 0x75, 0x75, 0x85, 0x94, 0xf4, 0x75, 0x81, 0xbb, 0xa5, 0xf4, 0x75, 0x87, 0x80, 0xba, + 0xf4, 0x75, 0x75, 0xb3, 0x8e, 0x9b, 0xf4, 0x75, 0x81, 0xbb, 0xae, 0xf4, 0x75, 0x87, 0xb3, 0x83, + /* bank # 38 */ + 0xa3, 0xf4, 0x75, 0x93, 0xf1, 0xb2, 0x8f, 0xb6, 0x9f, 0xbe, 0xbe, 0xb9, 0xaf, 0x7a, 0x8e, 0x9e, + 0x7e, 0xf5, 0xb3, 0x85, 0xb7, 0x95, 0x7c, 0x8e, 0x9e, 0x7c, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xb1, + 0xb5, 0x8f, 0x9f, 0xaf, 0xd0, 0x58, 0x82, 0xaf, 0x01, 0x2d, 0x55, 0x86, 0xaf, 0x42, 0x4e, 0x76, + 0x82, 0xa2, 0x00, 0x2c, 0x54, 0x84, 0xbd, 0xb6, 0x90, 0xaf, 0x51, 0xbd, 0xbd, 0xbd, 0xb5, 0x9f, + 0x06, 0xa4, 0xd0, 0x48, 0x8f, 0xaf, 0xd0, 0x0a, 0x84, 0x74, 0xa4, 0xd0, 0x3e, 0x80, 0x93, 0xaf, + 0x39, 0xd1, 0xab, 0xd9, 0xfa, 0xda, 0xdf, 0xd8, 0xba, 0xad, 0xfa, 0x83, 0x9b, 0xa7, 0x69, 0xdb, + 0xb2, 0x8d, 0xb6, 0x9d, 0x69, 0xf4, 0x26, 0x6d, 0xd8, 0xf1, 0xad, 0xde, 0xdf, 0xd8, 0xf0, 0xbc, + 0xb2, 0x81, 0xbd, 0xb6, 0x91, 0xbb, 0xa6, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xbc, 0xbc, + 0xbc, 0xb3, 0x86, 0xbd, 0xbd, 0xbd, 0xb7, 0x96, 0xa6, 0x2c, 0x54, 0x7c, 0x9b, 0x71, 0x97, 0xa5, + 0xd0, 0x2a, 0xf0, 0x50, 0x78, 0xf1, 0xd8, 0xb8, 0xac, 0xde, 0xf8, 0xf5, 0xb0, 0x8c, 0xb7, 0x93, + 0x06, 0xf1, 0xf9, 0xaf, 0xda, 0xf8, 0xd9, 0xde, 0xd8, 0xb3, 0xb6, 0xba, 0x86, 0xa7, 0xc2, 0xf4, + 0x75, 0x9b, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x84, 0x92, 0xf4, 0x75, 0x81, 0xf1, 0xa4, 0xf4, 0x75, + 0x87, 0x83, 0xa3, 0xf4, 0x75, 0x93, 0xb3, 0x86, 0xa7, 0xc4, 0xf4, 0x75, 0x9b, 0x95, 0xf0, 0x71, + 0x71, 0x60, 0x86, 0x92, 0xf4, 0x75, 0x81, 0xa6, 0xf4, 0x75, 0x87, 0x85, 0xa5, 0xf4, 0x75, 0x93, + 0xb3, 0x86, 0xa7, 0xc6, 0xf4, 0x75, 0x9b, 0x9f, 0xf0, 0x71, 0x71, 0x60, 0x88, 0x92, 0xf4, 0x75, + 0x81, 0xa8, 0xf4, 0x75, 0x87, 0x8f, 0xaf, 0xf4, 0x75, 0x93, 0xf5, 0xb2, 0x84, 0x94, 0xb9, 0xaf, + /* bank # 39 */ + 0x7c, 0x86, 0x96, 0x7c, 0x88, 0x98, 0x7c, 0xf1, 0xb1, 0x8f, 0xb5, 0x9f, 0xa5, 0x30, 0x85, 0x18, + 0xf0, 0x9a, 0x3c, 0x99, 0x18, 0xf1, 0xbc, 0xbc, 0xb2, 0x84, 0xb9, 0xaf, 0xc3, 0xc5, 0xc7, 0xba, + 0xb6, 0xbc, 0xbc, 0xa7, 0x8b, 0xb5, 0x9f, 0x2d, 0x55, 0x7d, 0xf5, 0xa7, 0x87, 0xb6, 0x97, 0x2c, + 0x54, 0x7c, 0xf0, 0xac, 0x81, 0x9c, 0x0c, 0x97, 0x28, 0x9c, 0x14, 0x97, 0x30, 0x9c, 0x1c, 0x97, + 0x38, 0xf1, 0xb1, 0x8f, 0xab, 0xc3, 0xc5, 0xc7, 0xa7, 0xb2, 0x81, 0x9c, 0x59, 0xdb, 0x51, 0xaa, + 0xde, 0xf4, 0x27, 0x6a, 0xd8, 0xf1, 0xac, 0xb1, 0x8e, 0x9c, 0x48, 0xfd, 0x02, 0xb2, 0x8b, 0x02, + 0xaa, 0xde, 0xa7, 0x8c, 0x11, 0xdb, 0x19, 0xda, 0xaa, 0xf8, 0xd8, 0xf1, 0xb5, 0xbd, 0xbd, 0x9b, + 0xfc, 0xc1, 0x03, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0xea, 0xd8, 0xf1, 0xb2, 0xbc, 0xbc, 0x84, 0xb8, + 0xbe, 0xae, 0xc3, 0xc5, 0xc7, 0xb0, 0xbc, 0xbc, 0xbc, 0xb4, 0xbd, 0xf0, 0x8a, 0x9e, 0xaf, 0x6c, + 0x99, 0x61, 0x8a, 0x19, 0x9e, 0x74, 0x99, 0x69, 0x8a, 0x39, 0x9e, 0x7c, 0x99, 0x71, 0x8a, 0x59, + 0xf1, 0x8f, 0x9f, 0xaa, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, 0x8e, 0xa9, 0xc2, + 0xc5, 0xc7, 0xf0, 0x8a, 0x9a, 0xa7, 0x04, 0x28, 0x50, 0xf1, 0x87, 0x97, 0xaf, 0x09, 0x8f, 0xb5, + 0xbd, 0xbd, 0xbd, 0x9b, 0x1e, 0xb4, 0xbd, 0x97, 0xa7, 0x20, 0x8b, 0xba, 0xa7, 0xc1, 0xc3, 0xc5, + 0xbd, 0xb6, 0x90, 0xfc, 0xc2, 0x00, 0xbd, 0xbd, 0xbd, 0xd9, 0xf4, 0x28, 0x77, 0xd8, 0xf1, 0xb2, + 0x86, 0xb6, 0x97, 0xa7, 0x4a, 0x99, 0xf4, 0x75, 0xa1, 0x9a, 0xf4, 0x75, 0x81, 0x8a, 0xaa, 0xf4, + 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x52, 0x9b, 0xf4, 0x75, 0xa1, 0x9c, 0xf4, 0x75, 0x81, 0x8c, + /* bank # 40 */ + 0xac, 0xf4, 0x75, 0x93, 0xf1, 0x86, 0x97, 0xa7, 0x5a, 0x9d, 0xf4, 0x75, 0xa1, 0x9e, 0xf4, 0x75, + 0x81, 0x8e, 0xae, 0xf4, 0x75, 0x93, 0xf1, 0x89, 0xa9, 0xc2, 0xc5, 0xc7, 0x87, 0xc3, 0x8b, 0xab, + 0xc2, 0xc5, 0xc7, 0x87, 0xc5, 0x8d, 0xad, 0xc2, 0xc5, 0xc7, 0x87, 0xc7, 0xb8, 0xae, 0xde, 0x8a, + 0xb4, 0x9e, 0x64, 0xfd, 0x01, 0x8c, 0x64, 0xfd, 0x01, 0x8e, 0x64, 0xfd, 0x01, 0xb0, 0xf0, 0x8d, + 0x9e, 0xaf, 0x6c, 0x9c, 0x61, 0x8d, 0x19, 0x9e, 0x74, 0x9c, 0x69, 0x8d, 0x39, 0x9e, 0x7c, 0x9c, + 0x71, 0x8d, 0x59, 0xf1, 0x8f, 0x9f, 0xad, 0x28, 0xfd, 0x01, 0x54, 0xfd, 0x01, 0x7c, 0xfd, 0x01, + 0x8e, 0xac, 0xc2, 0xc5, 0xc7, 0xf0, 0x8d, 0x9d, 0xa8, 0x04, 0x28, 0x50, 0xf1, 0x88, 0x98, 0xaf, + 0x09, 0x8f, 0x9b, 0x1e, 0x98, 0xa8, 0x20, 0xd8, 0xf1, 0xb8, 0xb1, 0xb4, 0xbc, 0xbc, 0xbc, 0x84, + 0xaf, 0xc7, 0x87, 0xc1, 0xb3, 0x83, 0xc1, 0xbc, 0xb0, 0x8f, 0x9f, 0xaf, 0x49, 0xda, 0xf4, 0x28, + 0xa7, 0xd8, 0xf5, 0x91, 0x7a, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xd9, + 0xa1, 0xde, 0xf8, 0xd8, 0xf4, 0x28, 0xb7, 0xd8, 0xf5, 0x91, 0x72, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, + 0xd9, 0xa1, 0xde, 0xdf, 0xa0, 0xde, 0xdf, 0xd8, 0xf1, 0xa1, 0xf8, 0xf9, 0xd1, 0xa0, 0xda, 0xf8, + 0xd9, 0xfa, 0xd8, 0x80, 0x90, 0xaf, 0x11, 0xdb, 0xa1, 0xde, 0x91, 0xfc, 0xc1, 0x04, 0xd9, 0xa1, + 0xf8, 0xdf, 0xa0, 0xde, 0xd8, 0x80, 0x90, 0xaf, 0x39, 0xd9, 0xa0, 0xde, 0xdf, 0xa1, 0xdf, 0xd8, + 0xf1, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xb1, 0xb5, 0xb9, 0xa6, + 0xf8, 0x8a, 0xbb, 0xa4, 0xc3, 0xa0, 0xc5, 0xb9, 0x86, 0x96, 0xaf, 0x21, 0xd9, 0xf4, 0x30, 0x31, + /* bank # 41 */ + 0xd8, 0xf1, 0xa6, 0xde, 0xa1, 0xde, 0xdf, 0xdf, 0xa0, 0xde, 0xdf, 0xdf, 0xdf, 0xab, 0xde, 0xac, + 0xde, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xb8, 0xbe, 0xbe, 0xbe, 0x83, 0xa9, + 0xc1, 0xf2, 0xbc, 0xbc, 0x82, 0xc3, 0x81, 0xc5, 0xf8, 0xf1, 0xb0, 0xbc, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x29, 0x84, 0xd8, 0xf1, 0xaa, 0xde, 0x99, 0xfc, 0xc1, 0x00, + 0xd9, 0xaa, 0xfa, 0xdb, 0x8a, 0x9a, 0xa9, 0x39, 0xaa, 0xde, 0xf8, 0xd8, 0xf5, 0xa2, 0x89, 0x92, + 0x3a, 0xf1, 0x92, 0xfc, 0xc0, 0x03, 0xda, 0xdf, 0xd9, 0xfa, 0xa2, 0x82, 0xdb, 0x31, 0xdf, 0xaa, + 0xde, 0xf8, 0xd8, 0x99, 0xfc, 0xc1, 0x03, 0xd9, 0xaa, 0xdf, 0xd8, 0xf2, 0x89, 0x99, 0xa9, 0x71, + 0xdb, 0xde, 0x41, 0xf1, 0xaa, 0xde, 0xf8, 0xd8, 0x9a, 0xfc, 0xc0, 0x04, 0xdb, 0xa8, 0xde, 0x98, + 0xfc, 0xc1, 0x00, 0xf8, 0xd8, 0xf1, 0xb1, 0xbc, 0xb5, 0xbd, 0xb9, 0xbe, 0x87, 0x94, 0xaf, 0x19, + 0xd9, 0x83, 0xa1, 0xc6, 0xf4, 0x2c, 0x7a, 0xd8, 0xf1, 0x82, 0x9f, 0xaf, 0xdf, 0x28, 0xfd, 0x03, + 0xdf, 0x30, 0xfd, 0x04, 0x8f, 0x9f, 0x34, 0x82, 0x38, 0x1d, 0xa9, 0xde, 0xd9, 0xf8, 0xda, 0xf4, + 0x2a, 0xeb, 0xd8, 0xf1, 0x82, 0x97, 0xaf, 0x51, 0xd9, 0x83, 0xa0, 0xc7, 0x83, 0xa7, 0xd0, 0xc2, + 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0x82, 0x92, 0xaf, 0x59, 0xda, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, 0xb3, + 0x83, 0xb7, 0x99, 0x1a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf5, + 0x3a, 0xf1, 0xf8, 0xf9, 0xd1, 0xda, 0xb1, 0xb5, 0xf4, 0x2a, 0x1c, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0xbc, 0x88, 0xaf, 0xc1, 0xf2, 0x89, 0xc5, 0xc7, 0xf9, 0xf9, 0xb1, 0xbc, 0xb5, 0xb9, 0xf2, 0x8f, + /* bank # 42 */ + 0x9f, 0xaf, 0x71, 0xd9, 0xf1, 0x83, 0xa0, 0xc6, 0xb3, 0x8c, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, + 0xc6, 0xb1, 0xb9, 0xd8, 0xf1, 0x83, 0xac, 0xc6, 0x83, 0xa7, 0xd0, 0xc4, 0xd8, 0xf1, 0xbc, 0xbc, + 0x81, 0xaf, 0xc3, 0xf3, 0x8b, 0xc3, 0xf2, 0xb3, 0x82, 0xc2, 0x81, 0xc5, 0xf9, 0xf1, 0xb1, 0xbc, + 0xbc, 0x83, 0x9f, 0xaf, 0x09, 0xdb, 0x8f, 0x9e, 0x31, 0x83, 0xa1, 0xc7, 0xa0, 0xdf, 0xd0, 0xde, + 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, + 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, 0x3f, 0xb5, 0xb9, 0xd8, 0x8f, 0x93, 0xaf, 0x21, + 0xdb, 0x83, 0xa0, 0xc7, 0xd0, 0xde, 0xa1, 0xdf, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf2, 0xaf, 0xde, + 0xf8, 0xf8, 0xf8, 0x8f, 0xdb, 0x41, 0xd9, 0xf1, 0x8e, 0xb7, 0x91, 0xbb, 0xa2, 0xd0, 0x5c, 0xfd, + 0x3f, 0xb5, 0xb9, 0xd8, 0xf1, 0x9f, 0xfc, 0xc2, 0x01, 0xd9, 0xf4, 0x2a, 0xba, 0xd8, 0xf3, 0xbc, + 0xbc, 0xaf, 0xd0, 0xb1, 0x8c, 0xc4, 0xf1, 0xb0, 0xbc, 0x8a, 0xaf, 0xc5, 0xb1, 0xbc, 0x80, 0x93, + 0xaf, 0x39, 0xd1, 0xd9, 0xf3, 0xd0, 0xf8, 0xf9, 0xdb, 0xd1, 0xf1, 0x9f, 0xfc, 0xc1, 0x04, 0xf2, + 0x8f, 0x9f, 0xaf, 0x59, 0xf1, 0xa0, 0xdf, 0x83, 0xd0, 0xc6, 0xd8, 0xf1, 0xa1, 0xd0, 0xde, 0x83, + 0x90, 0xaf, 0x69, 0xdb, 0x91, 0x69, 0xf4, 0x2a, 0xd4, 0xd8, 0xf2, 0x8f, 0x9f, 0x71, 0xd9, 0xf1, + 0x83, 0xa1, 0xd0, 0xc6, 0xd8, 0xf1, 0x80, 0x93, 0xaf, 0x19, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, + 0xf1, 0x79, 0xd1, 0xd9, 0xf4, 0x2b, 0x5a, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0x82, 0x9d, 0xaf, + 0x31, 0xda, 0xf4, 0x2b, 0x1c, 0xd8, 0xf1, 0x83, 0xa0, 0xd0, 0xc7, 0xb6, 0x9d, 0xfc, 0xc2, 0x04, + /* bank # 43 */ + 0xd9, 0xba, 0xad, 0xde, 0xf8, 0xd8, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0x88, 0xa4, + 0xd9, 0xc5, 0xa0, 0xc7, 0xda, 0xc1, 0xa0, 0xc3, 0xd8, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xa1, 0xf8, + 0xf9, 0xd1, 0xda, 0xf4, 0x2b, 0x5a, 0xd8, 0xf1, 0xba, 0xad, 0xf8, 0xf9, 0xd1, 0xd9, 0x83, 0xb9, + 0xa0, 0xc6, 0xab, 0xc6, 0xb3, 0x8d, 0xbb, 0xa4, 0xd0, 0xc4, 0xa0, 0xd0, 0xc6, 0xf4, 0x2b, 0x5a, + 0xd8, 0xf1, 0x83, 0xb9, 0xa0, 0xd0, 0xc7, 0xb3, 0x8a, 0xb7, 0x92, 0xbb, 0xaf, 0x19, 0xb1, 0xa4, + 0xd9, 0x89, 0xc3, 0xa0, 0xc5, 0xda, 0x88, 0xc1, 0xa0, 0xc3, 0xd8, 0xf1, 0xb1, 0x85, 0xba, 0xbe, + 0xaf, 0xc2, 0x84, 0xc7, 0x82, 0xc1, 0xc3, 0xb2, 0xbc, 0xb6, 0xbd, 0xa7, 0xdf, 0xdf, 0x8f, 0x92, + 0xa7, 0x01, 0xd9, 0xf4, 0x2b, 0x9c, 0xd8, 0xf1, 0x09, 0xd9, 0xf4, 0x2b, 0x83, 0xd8, 0xf1, 0xfa, + 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x51, 0xd9, 0xf4, 0x2b, 0x90, 0xd8, 0xf1, 0xfa, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x19, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x93, 0x21, + 0xd9, 0xf4, 0x2b, 0xb0, 0xd8, 0xf1, 0x09, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf4, 0x2b, 0xcb, + 0xd8, 0xf1, 0x71, 0xd9, 0xd0, 0xf8, 0xf4, 0x2b, 0xcb, 0xd8, 0xf1, 0x59, 0xd9, 0xd0, 0xf8, 0xf4, + 0x2b, 0xcb, 0xd8, 0xf1, 0x94, 0x01, 0xd9, 0xd0, 0xf8, 0xda, 0xfa, 0xd8, 0xf1, 0xb0, 0xbc, 0xbc, + 0x88, 0xa7, 0xc0, 0xb1, 0xbc, 0x89, 0xd0, 0xc1, 0x82, 0xaf, 0xd0, 0xc5, 0xb2, 0xbc, 0xb5, 0xbd, + 0x9b, 0xfc, 0xc1, 0x00, 0xb6, 0xbd, 0xbd, 0xbd, 0xdb, 0x97, 0xfc, 0xc3, 0x04, 0xfc, 0xc0, 0x00, + 0xfc, 0xc2, 0x04, 0xd9, 0xa7, 0xdf, 0xf8, 0xdf, 0xd8, 0xf1, 0x8f, 0x94, 0xa7, 0x71, 0xd9, 0xf4, + /* bank # 44 */ + 0x2c, 0x14, 0xd8, 0xf1, 0x95, 0x41, 0xd9, 0xf4, 0x2c, 0x14, 0xd8, 0xf1, 0x94, 0x09, 0xdb, 0x39, + 0xd9, 0xdf, 0xdf, 0xf8, 0xd8, 0xf1, 0x97, 0xfc, 0xc1, 0x04, 0xb1, 0xbc, 0xbc, 0xbc, 0x83, 0xb9, + 0xbe, 0xbe, 0xbe, 0xa0, 0xd9, 0xc6, 0xda, 0xde, 0xd8, 0xfc, 0xc2, 0x04, 0xd0, 0xd9, 0xc7, 0xda, + 0xdf, 0xd8, 0x8e, 0xb5, 0xbd, 0x9b, 0xaf, 0x4c, 0xbd, 0xbd, 0x9f, 0xfc, 0xc1, 0x00, 0xd9, 0xf4, + 0x2c, 0xbb, 0xd8, 0xf0, 0xb3, 0x86, 0xb6, 0x9a, 0xbb, 0xab, 0x2c, 0x50, 0x78, 0xf1, 0xba, 0xaa, + 0xc3, 0xc5, 0xc7, 0xb8, 0xad, 0xf8, 0xf9, 0xd1, 0xda, 0xde, 0xb3, 0x8e, 0xbb, 0xab, 0xc7, 0xd8, + 0xb3, 0x8e, 0xb7, 0x9b, 0xba, 0xa7, 0x69, 0xd9, 0xb1, 0x83, 0xb5, 0x90, 0x79, 0xdb, 0xd1, 0xb9, + 0xa0, 0xd0, 0xdf, 0xa1, 0xd0, 0xc6, 0xd8, 0xf4, 0x2c, 0xbb, 0xd8, 0xf1, 0xb0, 0xbc, 0x81, 0xb9, + 0xaf, 0xc0, 0xb0, 0x88, 0xc1, 0x87, 0xc1, 0xb1, 0xbc, 0xbc, 0xbc, 0xb5, 0xbd, 0xbd, 0x9b, 0xfc, + 0xc1, 0x00, 0xbd, 0xbd, 0xdb, 0x9f, 0xfc, 0xc0, 0x04, 0x8f, 0x9e, 0x2d, 0x8d, 0x9f, 0x31, 0xd9, + 0xa1, 0xde, 0x83, 0xa0, 0xc6, 0xaf, 0xde, 0xf8, 0xb3, 0x83, 0x9f, 0xf5, 0x06, 0xf1, 0xdb, 0xfc, + 0xc1, 0x04, 0xd9, 0xb8, 0xbe, 0xa1, 0xdf, 0xf8, 0xbe, 0xbe, 0xbe, 0xd8, 0xf5, 0xb3, 0x89, 0xb7, + 0x93, 0xbb, 0xa9, 0x66, 0x8b, 0xaf, 0x02, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0x8f, 0xa9, 0xd0, + 0xc0, 0xd8, 0x89, 0x99, 0xa3, 0x34, 0xaf, 0xde, 0xf8, 0xf5, 0x83, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, + 0x04, 0xdb, 0x95, 0x71, 0xa2, 0xd0, 0xde, 0xd8, 0xb0, 0x8d, 0xb9, 0xa1, 0xd0, 0xc7, 0x8f, 0xb4, + 0x9f, 0xaf, 0x11, 0xd9, 0xa1, 0xd0, 0xc7, 0xd8, 0xf1, 0xb3, 0x89, 0xbb, 0xaf, 0xc6, 0xf9, 0xf5, + /* bank # 45 */ + 0x8f, 0xb7, 0x93, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xdb, 0x83, 0xa9, 0xc0, 0xd8, 0xa3, 0xde, + 0xb9, 0xa0, 0xd0, 0xde, 0xba, 0xaa, 0xf8, 0xf9, 0xd1, 0xda, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0xb9, + 0xb1, 0xb5, 0xaf, 0x83, 0x90, 0x61, 0xdb, 0x69, 0x79, 0x91, 0x69, 0xf4, 0x2d, 0x85, 0xd8, 0xf1, + 0xdf, 0xf8, 0xa0, 0xfa, 0xf9, 0xd1, 0xd9, 0xaf, 0xdf, 0xd8, 0xaf, 0x8c, 0x95, 0x69, 0xd9, 0xdf, + 0xd8, 0xaf, 0x85, 0x9c, 0x31, 0xdb, 0x9f, 0xfc, 0xc1, 0x00, 0xda, 0xf4, 0x2d, 0x62, 0xd8, 0xf1, + 0x83, 0xa0, 0xd0, 0xc6, 0xaf, 0x8a, 0x9e, 0x11, 0xf8, 0xd9, 0xa0, 0xd0, 0x80, 0x9c, 0x48, 0xd8, + 0xaa, 0xde, 0xd8, 0xf1, 0xb3, 0x85, 0xb7, 0x95, 0xaf, 0x71, 0xb1, 0xb5, 0xd9, 0xa0, 0xd0, 0xde, + 0xd8, 0xf1, 0x83, 0xaf, 0xc6, 0xf8, 0x8f, 0x94, 0x1d, 0xdb, 0x90, 0xfc, 0xc0, 0x00, 0xa0, 0xd0, + 0xde, 0xd8, 0xf4, 0x2d, 0x8e, 0xd8, 0xf1, 0x61, 0xd1, 0xaa, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xf1, + 0xb1, 0x88, 0xbb, 0xa4, 0xd0, 0xc5, 0xa0, 0xd0, 0xc7, 0xb5, 0x90, 0xfc, 0xc2, 0x00, 0xd9, 0xb2, + 0x8e, 0xc6, 0xa4, 0xd0, 0xc5, 0xba, 0xae, 0xde, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0x84, 0xb4, 0x9f, + 0xba, 0xa7, 0x69, 0xda, 0xae, 0xf8, 0xf4, 0x2d, 0xbd, 0xd8, 0xf1, 0xae, 0xde, 0xd8, 0xf1, 0xb1, + 0x81, 0xb5, 0x9e, 0xbb, 0xaf, 0x02, 0xb7, 0x94, 0x26, 0xb3, 0x81, 0xb5, 0x9d, 0xa1, 0x02, 0xb7, + 0x90, 0x26, 0x8f, 0x91, 0xa1, 0x00, 0x2c, 0xb1, 0x80, 0x94, 0xaf, 0x12, 0x26, 0x5e, 0x6e, 0xb3, + 0x80, 0x92, 0xa2, 0x42, 0x0e, 0x76, 0x3e, 0x8f, 0xa2, 0x00, 0x2c, 0x54, 0x7c, 0xaf, 0xde, 0xf8, + 0xf5, 0x8f, 0x99, 0xaf, 0x06, 0xf1, 0x9f, 0xfc, 0xc1, 0x03, 0xd9, 0x8a, 0xaa, 0xc4, 0xd8, 0x83, + /* bank # 46 */ + 0x92, 0xaf, 0x51, 0xd9, 0xf4, 0x2e, 0x4b, 0xd8, 0xf1, 0xa2, 0xd0, 0xde, 0xb6, 0x9e, 0xfc, 0xc0, + 0x09, 0xdb, 0xfc, 0xc1, 0x0a, 0xd9, 0xb8, 0xae, 0xde, 0xba, 0xae, 0xde, 0xfa, 0xb7, 0xbb, 0xf4, + 0x2e, 0x4b, 0xd8, 0xf1, 0xb8, 0xae, 0xde, 0xf8, 0xba, 0xae, 0xdf, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, + 0xbe, 0xbe, 0xb0, 0xb4, 0xbb, 0xaf, 0xfb, 0xda, 0xb8, 0xa4, 0xd0, 0x8d, 0x94, 0x1d, 0xf1, 0xe2, + 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xb3, 0xb7, 0xbb, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, + 0x19, 0xd9, 0xf4, 0x2e, 0x8f, 0xd8, 0xf3, 0xbc, 0xbc, 0xb1, 0x8b, 0xc3, 0xbc, 0xbc, 0xb3, 0xf8, + 0xf9, 0xd1, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, 0xf1, 0x8e, 0x91, 0x41, 0xd9, 0xf4, 0x2e, 0x7d, 0xd8, + 0xf1, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0x81, 0xa2, 0xd0, 0xc7, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0xa3, + 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0x8b, 0xaa, 0xc6, 0xf4, 0x2f, 0x0a, 0xd8, + 0xf1, 0x81, 0xaa, 0xc6, 0x9a, 0x60, 0x60, 0xb1, 0x81, 0xb5, 0x93, 0xaf, 0x59, 0xb3, 0xb7, 0xd1, + 0xd9, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x8a, 0x92, 0xaf, 0x21, 0xda, 0xa3, 0xf8, 0xad, 0xde, 0xd8, + 0x81, 0xaa, 0xc5, 0x85, 0x91, 0xaf, 0x21, 0xd9, 0xf4, 0x2e, 0xe5, 0xd8, 0xf1, 0xa1, 0xdf, 0xa2, + 0xdf, 0xdf, 0x81, 0x95, 0xa5, 0xc7, 0x68, 0x89, 0x93, 0xa3, 0xc6, 0x60, 0xad, 0xf8, 0xaf, 0xde, + 0xf8, 0xf5, 0x89, 0x9f, 0x06, 0xf1, 0xfc, 0xc1, 0x03, 0xdb, 0x8d, 0x9d, 0xaf, 0x21, 0xa3, 0xde, + 0xf8, 0xd8, 0xf4, 0x2f, 0x0a, 0xd8, 0xf1, 0x81, 0xa5, 0xc5, 0x92, 0xaf, 0x49, 0xda, 0xa3, 0xf8, + 0xf8, 0xd8, 0x91, 0xaf, 0x49, 0xda, 0xa3, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xf1, 0xa3, 0xf8, 0xf9, + /* bank # 47 */ + 0xd1, 0xd9, 0xb1, 0x83, 0xb9, 0xa1, 0xd0, 0xc6, 0xb3, 0xbb, 0xd8, 0xf5, 0x83, 0x9a, 0xaf, 0x1a, + 0xf1, 0xbe, 0xb8, 0xae, 0xc1, 0x89, 0xb5, 0x9e, 0x74, 0xfd, 0x3f, 0xbc, 0xbc, 0xb1, 0x8b, 0x34, + 0xb7, 0x9f, 0xfc, 0xc0, 0x00, 0xbc, 0xbc, 0xbc, 0xb0, 0xbd, 0xb4, 0xd9, 0xf4, 0x2f, 0x64, 0xd8, + 0xf1, 0xa6, 0xf8, 0x86, 0x96, 0xae, 0x11, 0xd9, 0xa6, 0xdf, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, + 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, 0xbe, 0xbe, 0xdb, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, + 0xd9, 0xf2, 0xbe, 0xa1, 0xd0, 0xf8, 0xf8, 0xf8, 0xa2, 0xd0, 0xf8, 0xf8, 0xf8, 0xbe, 0xbe, 0xbe, + 0xd8, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0x9e, 0xfc, 0xc3, 0x01, 0xd9, 0xf5, 0x8e, 0xae, 0x32, 0xf1, + 0xdb, 0xfc, 0xc0, 0x01, 0x88, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, + 0xc6, 0xbe, 0xbe, 0xbe, 0xf4, 0x2f, 0xa2, 0xd8, 0xf1, 0xa6, 0xfa, 0x86, 0x96, 0xae, 0x39, 0xd9, + 0xa6, 0xde, 0x87, 0xbe, 0xbb, 0xa9, 0xd0, 0xc4, 0xf2, 0xa1, 0xd0, 0xc6, 0xa2, 0xd0, 0xc6, 0xbe, + 0xbe, 0xbe, 0xd8, 0xf1, 0xbc, 0xbc, 0xbc, 0xb3, 0xbd, 0xbd, 0xbd, 0xb7, 0xbe, 0xbe, 0xbe, 0xbb, + 0xa5, 0xf8, 0xf9, 0xd1, 0xda, 0x86, 0xa7, 0xc3, 0xc5, 0xc7, 0xa5, 0xde, 0x85, 0xa5, 0xd0, 0xc6, + 0xd8, 0x85, 0x95, 0xaf, 0x71, 0xda, 0xf4, 0x2f, 0xe2, 0xd8, 0xf1, 0x89, 0x93, 0xa3, 0x60, 0xf3, + 0xbe, 0xbe, 0xaf, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xe2, 0xd8, 0xf1, 0xbe, 0xbe, 0x86, 0xa7, 0xc3, + 0xc5, 0xc7, 0xd8, 0xf1, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x2d, 0x83, 0x0d, 0xf5, 0x99, 0xaf, 0x1a, + 0x8f, 0x7e, 0x9f, 0xa8, 0x12, 0x99, 0x2e, 0xf1, 0xdf, 0xdf, 0xaf, 0xdf, 0xf9, 0x89, 0x9f, 0x4d, + /* bank # 48 */ + 0x83, 0x0d, 0xf5, 0x9b, 0xaf, 0x02, 0x8f, 0x66, 0xf1, 0x9f, 0xfc, 0xc0, 0x03, 0xd9, 0xf5, 0xa8, + 0xd0, 0x12, 0x99, 0x36, 0xd8, 0xf1, 0x88, 0x98, 0xa6, 0x10, 0xa7, 0x38, 0x86, 0x9f, 0xaf, 0xde, + 0x00, 0xfd, 0x08, 0x87, 0x00, 0x8f, 0xf3, 0xae, 0xc0, 0xf1, 0xbc, 0xbc, 0xb1, 0x82, 0xc3, 0xbc, + 0xbc, 0xd8, 0xf3, 0xbc, 0xbc, 0xbd, 0xbd, 0xbe, 0xbe, 0xbb, 0xb3, 0xb7, 0xa2, 0xf8, 0xf2, 0xf8, + 0xf1, 0x80, 0x9d, 0xad, 0xd0, 0x7c, 0xf2, 0xa2, 0xfa, 0xf9, 0xd1, 0xf1, 0xb9, 0xac, 0xd9, 0xde, + 0xda, 0xf8, 0xd8, 0xf5, 0xbe, 0xbe, 0xba, 0xa7, 0x85, 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xbc, 0xbc, + 0xbd, 0xbd, 0xb2, 0xb6, 0xf1, 0xa9, 0x89, 0x99, 0x62, 0xf0, 0x97, 0x40, 0x99, 0x6c, 0x97, 0x48, + 0xb9, 0xb1, 0xb5, 0xf1, 0xaf, 0x80, 0x91, 0x28, 0x8c, 0x9f, 0x00, 0x83, 0x65, 0xd9, 0xf4, 0x30, + 0x94, 0xd8, 0xf1, 0x9d, 0xfc, 0xc3, 0x04, 0xaf, 0xb2, 0x89, 0xd9, 0xc3, 0xc1, 0xda, 0xc1, 0xc3, + 0xd8, 0xf4, 0x75, 0x55, 0xd8, 0xf2, 0xbe, 0xbe, 0xbc, 0xbc, 0xbd, 0xbd, 0xb9, 0xb3, 0xb7, 0xa6, + 0x81, 0x92, 0x49, 0xf9, 0xdb, 0xf1, 0xb1, 0x8c, 0xb5, 0x9c, 0x21, 0xd9, 0xf5, 0xb3, 0x85, 0xb7, + 0x95, 0x78, 0x8e, 0x9e, 0x7c, 0xf1, 0xb1, 0x8d, 0xb5, 0x9d, 0xad, 0x1a, 0xf0, 0x96, 0x40, 0x9d, + 0x3c, 0x96, 0x48, 0xd8, 0xf1, 0xb1, 0x81, 0xb5, 0x9d, 0xb9, 0xa6, 0x0a, 0x8d, 0x96, 0x05, 0xd9, + 0xf4, 0x30, 0xfb, 0xd8, 0xf2, 0xb3, 0x81, 0xb7, 0x92, 0xbb, 0xaf, 0x49, 0xf9, 0xf9, 0xdb, 0xf1, + 0xb1, 0x8c, 0xb5, 0x9c, 0xb9, 0xa6, 0x21, 0xf4, 0x30, 0xfb, 0xd8, 0xf1, 0xb3, 0x8e, 0xbb, 0xa8, + 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf4, 0x31, 0x0c, 0xd8, 0xf1, 0xb3, 0x85, 0xbb, + /* bank # 49 */ + 0xa8, 0xd0, 0xc4, 0xc7, 0xf3, 0xb9, 0xac, 0xd0, 0xde, 0xf8, 0xdf, 0xf8, 0xd8, 0xf3, 0xb5, 0x9c, + 0xfc, 0xc3, 0x04, 0xdb, 0xfc, 0xc2, 0x00, 0xd9, 0xf2, 0xac, 0xd0, 0xde, 0xd8, 0xf2, 0xbb, 0xaf, + 0xb7, 0x92, 0xb3, 0x82, 0x19, 0xdb, 0xa2, 0xdf, 0xa1, 0xd0, 0xc4, 0xac, 0xd0, 0xc5, 0xf3, 0xa7, + 0xd0, 0xdf, 0xf1, 0xb9, 0xaa, 0xde, 0xa1, 0xdf, 0xb5, 0x9b, 0xfc, 0xc1, 0x00, 0xb8, 0xbe, 0xa7, + 0xd0, 0xde, 0xbe, 0xbe, 0xbe, 0xd8, 0xf1, 0xbb, 0xaf, 0x89, 0xb7, 0x98, 0x19, 0xa9, 0x80, 0xd9, + 0x38, 0xd8, 0xaf, 0x89, 0x39, 0xa9, 0x80, 0xda, 0x3c, 0xd8, 0xa1, 0xf8, 0xf9, 0xd1, 0xda, 0xf9, + 0xdf, 0xf8, 0xf4, 0x75, 0x3d, 0xf1, 0xff, 0xd8, 0xaf, 0x2e, 0x88, 0xf5, 0x75, 0xda, 0xff, 0xd8, + 0x71, 0xda, 0xf1, 0xff, 0xd8, 0x82, 0xa7, 0xf3, 0xc1, 0xf2, 0x80, 0xc2, 0xf1, 0x97, 0x86, 0x49, + 0x2e, 0xa6, 0xd0, 0x50, 0x96, 0x86, 0xaf, 0x75, 0xd9, 0x88, 0xa2, 0xd0, 0xf3, 0xc0, 0xc3, 0xf1, + 0xda, 0x8f, 0x96, 0xa2, 0xd0, 0xf3, 0xc2, 0xc3, 0x82, 0xb6, 0x9b, 0x70, 0x70, 0xf1, 0xd8, 0xb7, + 0xaf, 0xdf, 0xf9, 0x89, 0x99, 0xaf, 0x10, 0x80, 0x9f, 0x21, 0xda, 0x2e, 0xd8, 0x89, 0x99, 0xaf, + 0x31, 0xda, 0xdf, 0xd8, 0xaf, 0x82, 0x92, 0xf3, 0x41, 0xd9, 0xf1, 0xdf, 0xd8, 0xaf, 0x82, 0xf3, + 0x19, 0xd9, 0xf1, 0xdf, 0xd8, 0xf1, 0x89, 0x90, 0xaf, 0xd0, 0x09, 0x8f, 0x99, 0xaf, 0x51, 0xdb, + 0x89, 0x31, 0xf3, 0x82, 0x92, 0x19, 0xf2, 0xb1, 0x8c, 0xb5, 0x9c, 0x71, 0xd9, 0xf1, 0xdf, 0xf9, + 0xf2, 0xb9, 0xac, 0xd0, 0xf8, 0xf8, 0xf3, 0xdf, 0xd8, 0xb3, 0xb7, 0xbb, 0x82, 0xac, 0xf3, 0xc0, + 0xa2, 0x80, 0x22, 0xf1, 0xa9, 0x22, 0x26, 0x9f, 0xaf, 0x29, 0xda, 0xac, 0xde, 0xff, 0xd8, 0xa2, + /* bank # 50 */ + 0xf2, 0xde, 0xf1, 0xa9, 0xdf, 0xf2, 0x82, 0xb8, 0xbe, 0xa9, 0xc3, 0x81, 0xc5, 0xb0, 0xbc, 0xf1, + 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xb4, 0xbd, 0xd9, 0xf4, 0x32, 0x33, 0xd8, 0xf2, 0x89, 0x99, 0xa9, + 0x49, 0xda, 0xf4, 0x32, 0x33, 0xd8, 0xf1, 0x9a, 0xfc, 0xc0, 0x04, 0xa7, 0xd0, 0xd9, 0x88, 0x97, + 0x30, 0xda, 0xde, 0xd8, 0xf1, 0xbc, 0xb1, 0x80, 0xbb, 0xbe, 0xbe, 0xbe, 0xaf, 0xc2, 0x8c, 0xc1, + 0x81, 0xc3, 0x83, 0xc7, 0xbc, 0xbc, 0xb3, 0x8f, 0xb7, 0xbd, 0xbd, 0xbd, 0x9f, 0xba, 0xa7, 0x61, + 0xdb, 0x69, 0x71, 0xff, 0xd8, 0xf1, 0xbb, 0xad, 0xd0, 0xde, 0xf8, 0xb1, 0x84, 0xb6, 0x96, 0xba, + 0xa7, 0xd0, 0x7e, 0xb7, 0x96, 0xa7, 0x01, 0xb2, 0x87, 0x9d, 0x05, 0xdb, 0xb3, 0x8d, 0xb6, 0x97, + 0x79, 0xf3, 0xb1, 0x8c, 0x96, 0x49, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, + 0xf8, 0xf9, 0xd1, 0xd9, 0xf1, 0xbb, 0xad, 0xd0, 0xf8, 0xd8, 0xb3, 0xb7, 0xbb, 0x97, 0x8c, 0xaf, + 0xf3, 0x79, 0xd9, 0xf4, 0x32, 0xa6, 0xd8, 0xf1, 0xa1, 0x81, 0x9d, 0x34, 0xaa, 0xd0, 0x8a, 0x50, + 0xf4, 0x75, 0x3d, 0xf4, 0x32, 0xc6, 0xd8, 0xf3, 0xa7, 0xd0, 0xfa, 0xb5, 0x9c, 0xfc, 0xc2, 0x07, + 0xd9, 0xf8, 0xd8, 0xb7, 0x97, 0x8c, 0xaf, 0x79, 0xda, 0xf1, 0x87, 0x91, 0xa1, 0x6c, 0xaa, 0xd0, + 0x9a, 0x70, 0xbb, 0xf4, 0x75, 0x3d, 0xd8, 0xf1, 0x91, 0xfc, 0xc1, 0x0a, 0xd9, 0xf4, 0x33, 0x07, + 0xd8, 0xf1, 0x81, 0xa1, 0xc2, 0xf9, 0xdf, 0xf8, 0x80, 0x9d, 0xba, 0xa6, 0xd0, 0x38, 0xfd, 0x31, + 0xbb, 0xaf, 0xde, 0xf3, 0x82, 0xce, 0xf1, 0x8f, 0x90, 0x08, 0xfd, 0x0f, 0x8d, 0x9f, 0x65, 0xd9, + 0xf4, 0x33, 0x07, 0xd8, 0xf1, 0xaf, 0xde, 0xf2, 0x8c, 0xce, 0xf2, 0x82, 0x9f, 0x25, 0xd9, 0xf1, + /* bank # 51 */ + 0xba, 0xa6, 0xd0, 0xde, 0xf3, 0x8d, 0xce, 0xd8, 0xf1, 0xb5, 0x9b, 0xfc, 0xc1, 0x03, 0xd9, 0xbc, + 0xbd, 0xbe, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xb8, 0xbe, 0xaa, 0xd0, 0xde, 0xf2, 0xb3, 0x81, 0xb7, + 0x92, 0xa9, 0x49, 0xd9, 0xbc, 0xbd, 0xf4, 0x33, 0x3b, 0xd8, 0xf1, 0xbc, 0xbd, 0xb0, 0xb4, 0x8d, + 0x97, 0x31, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xd9, 0xaa, 0xd0, 0xf8, 0xd8, 0xf1, 0xbc, 0xbc, 0xbd, + 0xbd, 0xbe, 0xbe, 0xb0, 0x84, 0xb8, 0xa5, 0xc3, 0xc5, 0xc7, 0x83, 0xa4, 0xc3, 0xc5, 0xc7, 0xf0, + 0xb2, 0x81, 0xb6, 0x91, 0xa3, 0x3c, 0x11, 0x0c, 0x58, 0x2c, 0x50, 0xf1, 0xb0, 0x83, 0xb4, 0x93, + 0xa3, 0x2c, 0x54, 0x7c, 0x92, 0x71, 0xf0, 0x95, 0xae, 0x2c, 0x50, 0x78, 0x8e, 0xbe, 0xb9, 0xaa, + 0xc2, 0xbc, 0xbd, 0xd8, 0xf2, 0xbb, 0xb3, 0xb7, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf4, 0x33, 0xdf, + 0xd8, 0xf1, 0x8d, 0xb7, 0x96, 0xbb, 0xa6, 0x40, 0xac, 0x8c, 0x9c, 0x0c, 0x30, 0xba, 0x8d, 0x9d, + 0xa7, 0x39, 0xdb, 0xf3, 0xb1, 0x8c, 0xb6, 0x96, 0x49, 0xd9, 0xf1, 0x84, 0xb5, 0x94, 0xb9, 0xa4, + 0xd0, 0x5e, 0xf0, 0xb7, 0x9d, 0x38, 0xd8, 0xf1, 0xb3, 0x8d, 0xba, 0xa7, 0xc6, 0xb5, 0x9c, 0xfc, + 0xc2, 0x04, 0xd9, 0xb1, 0x81, 0xb6, 0x97, 0xa7, 0x25, 0x8b, 0x6e, 0x81, 0xb9, 0xa1, 0x34, 0xda, + 0xb2, 0x87, 0xb6, 0x97, 0x00, 0xfd, 0x3e, 0xb1, 0x81, 0x25, 0x8b, 0x4e, 0x81, 0xb9, 0xa1, 0x34, + 0xd8, 0xf1, 0xbb, 0xaa, 0xd0, 0xdf, 0xac, 0xde, 0xd0, 0xde, 0xad, 0xd0, 0xdf, 0xf1, 0xff, 0xd8, + 0xf2, 0xb3, 0xb7, 0xaf, 0x82, 0x9c, 0x39, 0xdb, 0xf1, 0x86, 0x90, 0x09, 0xaa, 0xd0, 0x8a, 0x9d, + 0xd9, 0x74, 0xf4, 0x33, 0xfa, 0xda, 0xf1, 0xaa, 0xd0, 0xdf, 0xd8, 0xf3, 0xb9, 0xac, 0xd0, 0xf8, + /* bank # 52 */ + 0xf9, 0xd1, 0xd9, 0xf2, 0xbb, 0xa2, 0xfa, 0xf8, 0xda, 0xf2, 0xbb, 0xa2, 0xfa, 0xd8, 0xf2, 0xb3, + 0x82, 0xb6, 0x9b, 0xbb, 0xaf, 0x31, 0xdb, 0xf1, 0x89, 0xb5, 0x9a, 0x61, 0xd9, 0xf2, 0xa1, 0xd0, + 0xf8, 0xf8, 0xd8, 0xf2, 0x82, 0xaf, 0xc4, 0xf8, 0xf8, 0xf8, 0xf8, 0x8f, 0xb7, 0x91, 0x15, 0xda, + 0xa1, 0xd0, 0xc0, 0xd8, 0x82, 0xaf, 0xc2, 0xf9, 0xd1, 0xd9, 0xf1, 0xb9, 0xac, 0xde, 0xad, 0xde, + 0xdf, 0xb9, 0xa1, 0xdf, 0xbb, 0xad, 0xd0, 0xdf, 0xd8, 0xf2, 0x82, 0x91, 0xaf, 0x31, 0xda, 0xf1, + 0xb1, 0x81, 0x9d, 0xb9, 0xa1, 0x3c, 0xd8, 0xf2, 0xb3, 0xbb, 0x82, 0x91, 0xaf, 0x31, 0xd1, 0xd9, + 0xf1, 0xb1, 0x81, 0xb5, 0x9b, 0xb9, 0xa1, 0x3e, 0xd8, 0xf1, 0xb3, 0x8c, 0xb7, 0x9c, 0xbb, 0xac, + 0xd0, 0x10, 0xac, 0xde, 0xad, 0xd0, 0xdf, 0x92, 0x82, 0xaf, 0xf1, 0xca, 0xf2, 0x91, 0x35, 0xf1, + 0x96, 0x8f, 0xa6, 0xd9, 0x00, 0xdb, 0xaf, 0x8a, 0x90, 0x6d, 0xd9, 0xa6, 0x8f, 0x96, 0x01, 0x8a, + 0x60, 0xaa, 0xd0, 0xdf, 0xf2, 0x81, 0xac, 0xd0, 0xc5, 0xd8, 0xf1, 0xff, 0xd8, 0xf0, 0xb9, 0xb1, + 0xb6, 0xaf, 0x8d, 0x92, 0x4c, 0x71, 0x54, 0x68, 0x5c, 0x60, 0x44, 0x79, 0xe0, 0xd8, 0xf1, 0xba, + 0xb1, 0xa4, 0x8f, 0xc0, 0xc3, 0xc5, 0xc7, 0xb9, 0xb5, 0xf1, 0xaa, 0x82, 0x90, 0x25, 0xf3, 0xad, + 0xdf, 0xd9, 0xf8, 0xf8, 0xd8, 0xf1, 0xa1, 0x81, 0x91, 0xf0, 0x34, 0x82, 0x38, 0xf1, 0xaa, 0x2d, + 0xf5, 0x8a, 0x90, 0x30, 0xd9, 0xf3, 0xad, 0xfa, 0xd8, 0xf0, 0xaa, 0x8f, 0x9f, 0x04, 0x28, 0x51, + 0x79, 0x1d, 0x30, 0x14, 0x38, 0xbc, 0xbc, 0xbc, 0xa2, 0xd0, 0x8a, 0x9a, 0x2c, 0x50, 0x50, 0x78, + 0x78, 0xbc, 0x82, 0x90, 0xaa, 0xf5, 0x7c, 0xf3, 0xd9, 0xad, 0xfa, 0xd8, 0xf1, 0xb8, 0xae, 0x82, + /* bank # 53 */ + 0xc6, 0xb9, 0xa1, 0x81, 0x90, 0x0a, 0x81, 0x92, 0x18, 0xa2, 0xd0, 0x81, 0xc1, 0xf3, 0xad, 0xfb, + 0xf9, 0xf1, 0xda, 0xa2, 0xd0, 0xdf, 0xd8, 0xa2, 0xd0, 0xfa, 0xf9, 0xd1, 0xda, 0xaa, 0x82, 0x9d, + 0x7e, 0x76, 0xad, 0x8a, 0xd0, 0x31, 0x5c, 0xf0, 0xaa, 0x8d, 0x9d, 0x54, 0x78, 0xfd, 0x7f, 0xf1, + 0x8a, 0x92, 0x55, 0x9d, 0xad, 0xd0, 0x72, 0x7e, 0xd8, 0xf4, 0x74, 0x9c, 0xe0, 0xd8, 0xf1, 0xb1, + 0xb9, 0x82, 0xa2, 0xd0, 0xc2, 0xf2, 0xa3, 0xfa, 0xf3, 0xb8, 0xa7, 0xf8, 0xf9, 0xd1, 0xda, 0xf2, + 0xe2, 0xd8, 0xbb, 0xb3, 0xe0, 0xf1, 0xb1, 0xaf, 0x8f, 0x9f, 0x31, 0x85, 0xa5, 0xd0, 0xda, 0xc6, + 0xf4, 0x35, 0x72, 0xd8, 0xf1, 0xf8, 0xf9, 0xd1, 0xd9, 0xc6, 0xf5, 0xad, 0xd0, 0x8d, 0x9e, 0x7f, + 0xda, 0xf9, 0xd8, 0xf1, 0xe0, 0xf1, 0xb6, 0x97, 0xa7, 0x66, 0xb7, 0x93, 0xf0, 0x71, 0x71, 0x60, + 0xe0, 0xf0, 0x01, 0x29, 0x51, 0x79, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xb6, 0x97, 0x2c, + 0xfd, 0x01, 0xe0, 0xf1, 0xc2, 0xc5, 0xc7, 0xb2, 0x87, 0xc1, 0xe0, 0xf1, 0xb2, 0x81, 0x97, 0x66, + 0xe0, 0xf0, 0x38, 0x10, 0x28, 0x40, 0x88, 0xe0, 0xf0, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, + 0x48, 0x31, 0x2d, 0x51, 0x79, 0xe0, 0xf0, 0x24, 0x58, 0x3d, 0x40, 0x34, 0x49, 0x2d, 0x51, 0xe0, + 0xf1, 0x87, 0xa1, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x81, 0xa7, 0x04, 0x28, 0x50, 0x78, 0xfd, 0x7f, + 0xf1, 0xa7, 0x87, 0x96, 0x59, 0x91, 0xa1, 0x02, 0x0e, 0x16, 0x1e, 0xe0, 0xd8, 0xf0, 0xbe, 0xbe, + 0xbe, 0xbc, 0xbc, 0xbc, 0xbd, 0xbd, 0xbd, 0xb3, 0xbb, 0x8c, 0xac, 0xf4, 0x78, 0x59, 0x8d, 0xad, + 0xf4, 0x78, 0x59, 0x8e, 0xae, 0xf4, 0x78, 0x59, 0xbc, 0xb0, 0x80, 0xba, 0xaf, 0xf1, 0xde, 0xdf, + /* bank # 54 */ + 0xdf, 0xd0, 0xf2, 0xc2, 0xcb, 0xc5, 0xbc, 0xbc, 0xbc, 0xb2, 0x8f, 0xd0, 0xbd, 0xb5, 0x9e, 0xf1, + 0x02, 0xfd, 0x03, 0x26, 0xfd, 0x03, 0x46, 0xfd, 0x03, 0xbd, 0xbd, 0xbd, 0xb5, 0x90, 0xbb, 0xaf, + 0x02, 0xf0, 0x28, 0x50, 0xf1, 0x1e, 0x91, 0xf0, 0x20, 0x48, 0xf1, 0x16, 0xf0, 0x38, 0x92, 0x40, + 0xb3, 0xb7, 0x8f, 0xf2, 0xac, 0xc0, 0xad, 0xc2, 0xae, 0xc4, 0xf1, 0xa9, 0xfa, 0xf9, 0xd1, 0xd9, + 0xf4, 0x36, 0x4a, 0xd8, 0xf1, 0xa9, 0xfa, 0xf4, 0x38, 0x1c, 0xd8, 0xf0, 0xb7, 0x8c, 0x9c, 0xba, + 0xf4, 0x78, 0x28, 0xf1, 0xc1, 0xb3, 0x8d, 0x9d, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8e, + 0x9e, 0xba, 0xf4, 0x78, 0x28, 0xf1, 0x1c, 0xb3, 0x8f, 0xd7, 0xfd, 0x3e, 0xf2, 0x8d, 0xc1, 0x8e, + 0xc1, 0xf1, 0x8f, 0xd5, 0xfd, 0x30, 0xd4, 0xd0, 0xfd, 0x70, 0xf1, 0xd0, 0x2a, 0xd2, 0xf0, 0x00, + 0xd2, 0xa9, 0xde, 0x8f, 0xb5, 0x97, 0xaf, 0xf5, 0x40, 0xd9, 0xf2, 0xa9, 0xf8, 0xd8, 0x97, 0xaf, + 0xf5, 0x48, 0xd9, 0xf3, 0xa9, 0xf8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0xb7, 0x8f, + 0x9d, 0x05, 0xda, 0xf4, 0x36, 0xc3, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, + 0x3f, 0xfd, 0x0e, 0x8d, 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xd8, 0xf2, 0xaf, 0xde, 0xf8, 0xd4, 0xfd, 0x0c, 0x8f, 0x9e, 0x05, 0xda, 0xf4, + 0x36, 0xee, 0xd8, 0xf2, 0xb5, 0x97, 0xde, 0xf8, 0xd0, 0x37, 0xfd, 0x0e, 0x3f, 0xfd, 0x0e, 0x8e, + 0xb7, 0x9f, 0xd0, 0x05, 0xd9, 0xa9, 0xf8, 0xd8, 0xaf, 0x0d, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf1, + 0x8c, 0xaf, 0xde, 0xf2, 0xc0, 0x8f, 0xf0, 0xd4, 0xfd, 0x30, 0x9f, 0xf5, 0x00, 0xb1, 0x88, 0x04, + /* bank # 55 */ + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xf5, 0xaf, 0x24, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xf0, 0xaf, 0xb3, + 0x89, 0xc4, 0xc7, 0x8f, 0xd0, 0xd4, 0xfd, 0x40, 0xd5, 0xfd, 0x40, 0xb1, 0x88, 0xd0, 0xf5, 0x44, + 0xd9, 0xa9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x6c, 0xd9, 0xa9, 0xf3, 0xf8, 0xd8, 0xb3, 0x8f, 0xb5, + 0x99, 0xf5, 0xaf, 0x60, 0xd9, 0xaa, 0xf8, 0xf4, 0x37, 0x45, 0xd8, 0xf1, 0xb1, 0x8a, 0xb7, 0x9f, + 0xaf, 0x59, 0xd9, 0xaa, 0xde, 0xd8, 0xf5, 0xb3, 0x8f, 0xb5, 0x99, 0xaf, 0x68, 0xd9, 0xaa, 0xfa, + 0xda, 0xaa, 0xdf, 0xd8, 0xf1, 0x8a, 0xaf, 0xd4, 0xfd, 0x00, 0xd5, 0xfd, 0x40, 0x8f, 0xd0, 0xf5, + 0x14, 0xa9, 0xd0, 0xd9, 0xde, 0xda, 0xf8, 0xd8, 0xaf, 0x3c, 0xa9, 0xd0, 0xd9, 0xdf, 0xda, 0xfa, + 0xd8, 0xf1, 0x8a, 0xaf, 0xd6, 0xfd, 0x00, 0xd7, 0xfd, 0x40, 0x8f, 0x9a, 0xd0, 0xf5, 0x04, 0xa9, + 0xd9, 0xf2, 0xf8, 0xd8, 0xaf, 0xf5, 0x2c, 0xa9, 0xd9, 0xf3, 0xf8, 0xd8, 0x8c, 0xaf, 0xf2, 0xc0, + 0xf1, 0x8f, 0xd4, 0xfd, 0x30, 0xb7, 0x9f, 0x02, 0xfd, 0x1e, 0xd0, 0x10, 0xaf, 0xde, 0xf8, 0xf8, + 0xf8, 0xf8, 0xf8, 0xf8, 0xbd, 0xbd, 0xbd, 0x93, 0xf5, 0x02, 0xf1, 0xbd, 0xf8, 0xf9, 0xd1, 0xda, + 0xf4, 0x37, 0xbd, 0xd8, 0xf1, 0xb1, 0x8a, 0x9f, 0x59, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb1, + 0x8b, 0x9f, 0xaf, 0x51, 0xda, 0xf4, 0x37, 0xd3, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x41, 0xd9, + 0xa9, 0xf2, 0xf8, 0xd8, 0xf1, 0xaf, 0xb7, 0x9f, 0xb1, 0x8a, 0x79, 0xda, 0xf4, 0x37, 0xf2, 0xd8, + 0xf1, 0x8b, 0x71, 0xda, 0xf4, 0x37, 0xf2, 0xd8, 0xf1, 0xb5, 0x9b, 0xb3, 0x8f, 0x49, 0xd9, 0xa9, + 0xf3, 0xf8, 0xd8, 0xf0, 0xa9, 0xf2, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xaa, 0xd0, 0xf0, + /* bank # 56 */ + 0xda, 0xde, 0xf5, 0xe2, 0xf0, 0xd9, 0xf8, 0xd8, 0xa9, 0xf3, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, 0xf9, + 0xf9, 0xaa, 0xd0, 0xf0, 0xda, 0xdf, 0xf6, 0xe2, 0xf0, 0xd9, 0xfa, 0xd8, 0xd8, 0xf0, 0xbc, 0xb0, + 0x80, 0xbd, 0xb4, 0x90, 0xbe, 0xb8, 0xa0, 0xe0, 0xf0, 0xaf, 0xf2, 0x11, 0x3d, 0xf3, 0x15, 0x3d, + 0xf2, 0xb2, 0x8f, 0xd0, 0xcd, 0xcf, 0xf3, 0xdf, 0xdf, 0xdf, 0xdf, 0xf1, 0xd4, 0xfd, 0x70, 0xd5, + 0xfd, 0x70, 0xd6, 0xfd, 0x70, 0xd7, 0xfd, 0x70, 0xb6, 0x9f, 0x0c, 0x10, 0x18, 0xf5, 0x00, 0xb5, + 0x96, 0xf5, 0x18, 0xbb, 0xaf, 0xd0, 0xb7, 0x9f, 0xe0, 0xf0, 0xd0, 0xf3, 0xcf, 0xf2, 0xcc, 0xd0, + 0xf3, 0xcd, 0xf2, 0xca, 0xd0, 0xf3, 0xcb, 0xf2, 0xc8, 0xd0, 0xf3, 0xc9, 0xe0 \ No newline at end of file diff --git a/lib/INA209/INA209.cpp b/lib/INA209/INA209.cpp new file mode 100644 index 0000000..15486dd --- /dev/null +++ b/lib/INA209/INA209.cpp @@ -0,0 +1,246 @@ +/* + INA209.cpp - Library for Texas Instruments INA209 + Created 10 Aug. 2012 (Rev. 1.0) + Copyright (c) 2012 Antonio Dambrosio . All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. +*/ + +#include "INA209.h" + +//<> +INA209::INA209(int address){ + i2c_addr = address; +} +//<> +INA209::~INA209(){/*nothing to destruct*/} + +// positioning on register pointer address +void INA209::pointReg(int p_address) { + Wire.beginTransmission(i2c_addr); + Wire.write(p_address); + Wire.endTransmission(); +} +// read a word from the register pointed +word INA209::readWord() { + Wire.requestFrom(i2c_addr, 2); // read 2 bytes from register + byte MSB = Wire.read(); + byte LSB = Wire.read(); + return word(MSB,LSB); +} +// write a word into the register pointed +void INA209::writeWord(int p_address, word wordToW) { + Wire.beginTransmission(i2c_addr); + Wire.write(p_address); + Wire.write(highByte(wordToW)); + Wire.write(lowByte(wordToW)); + Wire.endTransmission(); +} + +// ----------------------- Config/Status REGISTERS ---------------------------------------- +// Configuration Register (All-register reset, settings for bus, voltage range, PGA Gain, ADC, resolution/averaging). +word INA209::readCfgReg(){ + pointReg(0x00); + return readWord(); +} +void INA209::writeCfgReg(word CfgReg){ + writeWord(0x00,CfgReg); +} +// read Status Register (Status flags for warnings,over-/under-limits, conversion ready,math overflow, and SMBus Alert).). +word INA209::statusReg(){ + pointReg(0x01); + return readWord(); +} +// SMBus Alert Mask/Enable Control Register(Enables/disables flags in the Status Register). +word INA209::readSMBusCtrlReg(){ + pointReg(0x02); + return readWord(); +} +void INA209::writeSMBusCtrlReg(word SMBusCtrlReg){ + writeWord(0x02,SMBusCtrlReg); +} + +// ----------------------- DATA OUTPUT REGISTERS ---------------------------------------- +// Shunt Voltage (Shunt voltage measurement data). +int INA209::shuntVol(){ + pointReg(0x03); + return int(readWord()); // returns integer value LSB=10uV +} +// Bus Voltage (Bus Voltage 12bit measurement data; +// ; at full-scale range = 32V (decimal = 8000, hex = 1F40), and LSB = 4mV +// ; at full-scale range = 16V (decimal = 4000, hex = 0FA0), and LSB = 4mV). +int INA209::busVol(){ + pointReg(0x04); + return int(readWord() >> 1); // returns mV integer value +} +// Power (Power measurement data). +// Full-scale range and LSB depend on the value entered in the Calibration Register (see the datasheet). +int INA209::power(){ + pointReg(0x05); + return int(readWord()); +} +// Current (Contains the value of the current flowing through the shunt resistor). +// Full-scale range and LSB depend on the value entered in the Calibration Register (see the datasheet). +int INA209::current(){ + pointReg(0x06); + return int(readWord()); +} + +// ----------------------- PEAK-HOLD REGISTERS ---------------------------------------- +// Note: All peak-hold registers are cleared and reset to POR values by writing a '1' into the respective D0 bits. + +// Shunt Voltage Positive Peak (Contains most positive voltage reading of Shunt Voltage Register). +int INA209::readShuntVolPpk(){ + pointReg(0x07); + return int(readWord()); +} +void INA209::writeShuntVolPpk(word ShuntVolPpk){ + writeWord(0x07,ShuntVolPpk); +} +// Shunt Voltage Negative Peak (Contains most negative voltage reading of Shunt Voltage Register). +int INA209::readShuntVolNpk(){ + pointReg(0x08); + return int(readWord()); +} +void INA209::writeShuntVolNpk(word ShuntVolNpk){ + writeWord(0x08,ShuntVolNpk); +} +// Bus Voltage Maximum Peak (Contains highest voltage reading of Bus Voltage Register). +int INA209::readBusVolMaxPk(){ + pointReg(0x09); + return int(readWord() >> 1); +} +void INA209::writeBusVolMaxPk(word BusVolMaxPk){ + writeWord(0x09,BusVolMaxPk); +} +// Bus Voltage Minimum Peak (Contains lowest voltage reading of Bus Voltage Register). +int INA209::readBusVolMinPk(){ + pointReg(0x0A); + return int(readWord() >> 1); +} +void INA209::writeBusVolMinPk(word BusVolMinPk ){ + writeWord(0x0A,BusVolMinPk); +} +// Power Peak (Contains highest power reading of Power Register). +word INA209::readPowerPk(){ + pointReg(0x0B); + return readWord(); +} +void INA209::writePowerPk(word PowerPk){ + writeWord(0x0B,PowerPk); +} + +// ----------------------- WARNING WATCHDOG REGISTERS ---------------------------------------- +// These registers set warning limits that trigger flags in the Status Register and activate the Warning pin. + +// Shunt Voltage Positive Warning (Warning watchdog register. Sets positive shunt voltage limit that triggers a warning flag in the Status Register, and activates Warning pin). +int INA209::readShuntVolPwrn(){ + pointReg(0x0C); + return int(readWord()); +} +void INA209::writeShuntVolPwrn(word ShuntVolPwrn){ + writeWord(0x0C,ShuntVolPwrn); +} +// Shunt Voltage Negative Warning (Warning watchdog register. Sets negative shunt voltage limit that triggers a warning flag in the Status Register, and activates Warning pin). +int INA209::readShuntVolNwrn(){ + pointReg(0x0D); + return int(readWord()); +} +void INA209::writeShuntVolNwrn(word ShuntVolNwrn){ + writeWord(0x0D,ShuntVolNwrn); +} +// Power Warning (Warning watchdog register. Sets power limit that triggers a warning flag in the Status Register, and activates Warning pin). +word INA209::readPowerWrn(){ + pointReg(0x0E); + return readWord(); +} +void INA209::writePowerWrn(word writePowerWrn){ + writeWord(0x0E,writePowerWrn); +} +// Bus Over-Voltage Warning (Warning watchdog register. Sets high Bus voltage limit that triggers a warning flag in the Status Register, and activates Warning pin. Also contains bits to set Warning pin polarity and latch feature). +word INA209::readBusOVwrn(){ + pointReg(0x0F); + return readWord(); +} +void INA209::writeBusOVwrn(word BusOVwrn){ + writeWord(0x0F,BusOVwrn); +} +// Bus Under-Voltage Warning (Warning watchdog register. Sets low Bus voltage limit that triggers a warning flag in the Status Register, and activates Warning pin). +word INA209::readBusUVwrn(){ + pointReg(0x10); + return readWord(); +} +void INA209::writeBusUVwrn(word BusUVwrn){ + writeWord(0x10,BusUVwrn); +} + +// ----------------------- OVER-LIMIT/CRITICAL WATCHDOG REGISTERS ---------------------------------------- +// These registers set the over-limit and critical DAC limits that trigger flags to be set in the Status Register and activate the Overlimit pin or the Critical pin. + +// Power Over-Limit (Over-limit watchdog register. Sets power limit that triggers an over-limit flag in the Status Register, and activates the Overlimit pin). +word INA209::readPowerOL(){ + pointReg(0x11); + return readWord(); +} +void INA209::writePowerOL(word PowerOL){ + writeWord(0x11,PowerOL); +} +// Bus Over-Voltage Over-Limit(Over-limit watchdog register. Sets Bus over-voltage limit that triggers an over-limit flag in the Status Register, and activates the Overlimit pin. Also contains bits to set Overlimit pin polarity and latch feature). +word INA209::readBusOVOL(){ + pointReg(0x12); + return readWord(); +} +void INA209::writeBusOVOL(word BusOVOL){ + writeWord(0x12,BusOVOL); +} +// Bus Under-Voltage Over-Limit(Over-limit watchdog register. Sets Bus under-voltage limit that triggers an over-limit flag in the Status Register, and activates the Overlimit pin). +word INA209::readBusUVOL(){ + pointReg(0x13); + return readWord(); +} +void INA209::writeBusUVOL(word BusUVOL){ + writeWord(0x13,BusUVOL); +} +// Critical Shunt Positive Voltage(Sets a positive limit for internal Critical DAC+. Contains bits for GPIO pin status and mode of operation, Critical Comparator latch feature and hysteresis). +word INA209::readCrShuntPV(){ + pointReg(0x14); + return readWord(); +} +void INA209::writeCrShuntPV(word CrShuntPV){ + writeWord(0x14,CrShuntPV); +} +// Critical Shunt Negative Voltage(Sets a negative limit for internal Critical DAC-. Contains bits for Warning pin delay, and Critical Comparator output filter configuration). +word INA209::readCrShuntNV(){ + pointReg(0x15); + return readWord(); +} +void INA209::writeCrShuntNV(word CrShuntNV){ + writeWord(0x15,CrShuntNV); +} +// Calibration(Sets full-scale range and LSB of current and power measurements. Overall system calibration.). +word INA209::readCal(){ + pointReg(0x16); + return readWord(); +} +void INA209::writeCal(word cal){ + writeWord(0x16,cal); +} + + + + + + + + + + + diff --git a/lib/INA209/INA209.h b/lib/INA209/INA209.h new file mode 100644 index 0000000..34b13f1 --- /dev/null +++ b/lib/INA209/INA209.h @@ -0,0 +1,77 @@ +/* + INA209.h - Library for Texas Instruments INA209 + Created 10 Aug. 2012 (Rev. 1.0) + Copyright (c) 2012 Antonio Dambrosio . All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. +*/ + +#ifndef INA209_H +#define INA209_H + +#include +#include + +class INA209 { + int i2c_addr; + int p_addr; +private: + word readWord(); + void writeWord(int p_address, word wordToW); + void pointReg(int p_address); +public: + INA209(void){} + INA209(int address); + ~INA209(); + word readCfgReg(); + void writeCfgReg(word CfgReg); + word statusReg(); + word readSMBusCtrlReg(); + void writeSMBusCtrlReg(word SMBusCtrlReg); + int shuntVol(); + int busVol(); + int power(); + int current(); + int readShuntVolPpk(); + void writeShuntVolPpk(word ShuntVolPpk); + int readShuntVolNpk(); + void writeShuntVolNpk(word ShuntVolNpk); + int readBusVolMaxPk(); + void writeBusVolMaxPk(word BusVolMaxPk); + int readBusVolMinPk(); + void writeBusVolMinPk(word BusVolMinPk); + word readPowerPk(); + void writePowerPk(word PowerPk); + int readShuntVolPwrn(); + void writeShuntVolPwrn(word ShuntVolPwrn); + int readShuntVolNwrn(); + void writeShuntVolNwrn(word ShuntVolNwrn); + word readPowerWrn(); + void writePowerWrn(word PowerWrn); + word readBusOVwrn(); + void writeBusOVwrn(word BusOVwrn); + word readBusUVwrn(); + void writeBusUVwrn(word BusUVwrn); + word readPowerOL(); + void writePowerOL(word PowerOL); + word readBusOVOL(); + void writeBusOVOL(word BusOVOL); + word readBusUVOL(); + void writeBusUVOL(word BusUVOL); + word readCrShuntPV(); + void writeCrShuntPV(word CrShuntPV); + word readCrShuntNV(); + void writeCrShuntNV(word CrShuntNV); + word readCal(); + void writeCal(word cal); +}; + +#endif diff --git a/lib/INA209/example/INA209_read_write_registers/INA209_read_write_registers.ino b/lib/INA209/example/INA209_read_write_registers/INA209_read_write_registers.ino new file mode 100644 index 0000000..e2dbee5 --- /dev/null +++ b/lib/INA209/example/INA209_read_write_registers/INA209_read_write_registers.ino @@ -0,0 +1,161 @@ +/* + Texas Instruments INA209 Library + Created 10 Aug. 2012 (Rev. 1.0) + Copyright (c) 2012 Antonio Dambrosio . All right reserved. + + This example demonstrates the I2C communication with an INA209 chip + (High-Side Measurement, Bi-Directional Current/Power Monitor) + The INA209 library works only with the Texas Instruments INA209 chips. + + The circuit: + INA209 PIN 1 (Vin+) <-> to positive side of 0,1 Ohm shunt resistor + INA209 PIN 2 (Vin-) <-> to negative side of 0,1 Ohm shunt resistor + INA209 PIN 4 (GND) <-> to power supply ground + INA209 PIN 5 (Vs+) <-> to power supply 3V to 5,5V + INA209 PIN 10 (Vs+) <-> to power supply 3V to 5,5V + INA209 PIN 11 (GND) <-> to power supply ground + INA209 PIN 12 (SCL) <-> ANALOG PIN 5 for ARDUINO UNO + INA209 PIN 13 (SDA) <-> ANALOG PIN 4 for ARDUINO UNO + INA209 PIN 14 (A0) <-> to power supply ground for set slave address to 0x40 + INA209 PIN 15 (A1) <-> to power supply ground for set slave address to 0x40 + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. +*/ + +// include the library code: +#include //I2C library +#include + +INA209 ina209a(0x40); // creation of an instance of the INA209 class called ina209a with I2C slave address = 0x40 + +void setup() { + Serial.begin(9600); // setup serial + Wire.begin(); // join i2c bus + + // ------------- General Configuration --------- + /* Configuration Register 00h (Read/Write) + Default settings -> writeCfgReg(14751) + Bus Voltage Range = 32V + PGA (Shunt Voltage Only) = +/- 320mV + BADC Bus ADC Resolution/Averaging = 12bit + SADC Shunt ADC Resolution/Averaging = 12bit + Operating Mode = Shunt and Bus, Continuos + */ + ina209a.writeCfgReg(14751); // Default settings + + // -------------- Calibration ------------------ + /* Calibration Register 16h (Read/Write) + This register sets the current that corresponds to a full-scale drop across the shunt. + Full-scale range and the LSB of the current and power measurement depend on the value entered in this register. + See the Programming the INA209 Power Measurement Engine section of INA209 datasheet. + In this example: + Vbus_max = 32V + Vshunt_max = 0,32V + Rshunt = 0,1 Ohm + -> Max Expected Current = +/- 3A + Current LSB = 100uA + Calibration Reg = 4096 + Power LSB = 2mW + Mas Power = 102,4W + */ + ina209a.writeCal(4096); + + // ---------- WARNING WATCHDOG REGISTERS ------- + /* These registers set warning limits that trigger flags in the Status Register + and activate the Warning pin. + */ + ina209a.writeShuntVolPwrn(30000); // set Shunt Voltage Positive Warning limit to 30000 (= 300mV) + ina209a.writeShuntVolNwrn(-500); // set Shunt Voltage Negative Warning limit to -500 (= -5mV) + ina209a.writePowerWrn(10000); // set Power Warning limit + ina209a.writeBusOVwrn(52000); // set Bus Over-Voltage Warning limit, if you want a limit of 26V you have to set 26000*2 = 52000 + ina209a.writeBusUVwrn(10000); // set Bus Under-Voltage Warning limit, if you want a limit of 5V you have to set 5000*2 = 10000 + + // ---------- OVER-LIMIT/CRITICAL WATCHDOG REGISTERS ---------------- + /* These registers set the over-limit and critical DAC limits that trigger flags to be set in the Status Register + and activate the Overlimit pin or the Critical pin. + */ + ina209a.writePowerOL(12000); // set Power Over-Limit + ina209a.writeBusOVOL(60000); // set Bus Over-Voltage Over-Limit, if you want a limit of 30V you have to set 30000*2 = 60000 (see the datasheet for other functions) + ina209a.writeBusUVOL(6000); // set Bus Under-Voltage Over-Limit, if you want a limit of 3V you have to set 3000*2 = 6000 + ina209a.writeCrShuntPV(51200); // set Critical DAC+ Register (Critical Shunt Positive Voltage). No sign bit (sets a positive limit only). At full-scale range = 255mV; LSB = 1mV; 8-bit. + // if you want a limit of +200mV you have to set 200*256 = 51200; + // this register control GPIO PIN, see the datasheet. + ina209a.writeCrShuntNV(51200); // set Critical DAC– Register (Critical Shunt Negative Voltage). No sign bit (sets negative limit only). At full-scale range = –255mV; LSB = 1mV; 8-bit. + // if you want a limit of -200mV you have to set 200*256 = 51200; + // this register control DAC Comparator output filter, see the datasheet. + } + +void loop() { + + // ----------------------- CONFIG AND STATUS REGISTERS ---------------------------------- + Serial.println(" Configuration Register "); + Serial.println(ina209a.readCfgReg()); + Serial.println(" Status Register "); + Serial.println(ina209a.statusReg()); + Serial.println(" SMBus Alert "); + Serial.println(ina209a.readSMBusCtrlReg()); + + // ----------------------- DATA OUTPUT REGISTERS ---------------------------------------- + Serial.println(" Bus Voltage "); + Serial.println(ina209a.busVol()); // returns integer value Bus Voltage measurement in mV (Bus Voltage LSB=4mV) + Serial.println(" Shunt Voltage "); + Serial.println(ina209a.shuntVol()); // returns integer value Shunt Voltage measurement data with LSB=10uV + Serial.println(" Current "); + Serial.println(ina209a.current()); // returns integer value of the Current flowing through the shunt resistor with LSB=100uA (= ShuntVoltage * CalReg / 4096) + Serial.println(" Power "); + Serial.println(ina209a.power() << 1); // returns integer value Power measurement in mW (in this example = register value * Power LSB=2mW) + + // ----------------------- PEAK-HOLD REGISTERS ----------------------------------------- + // Note: All peak-hold registers are cleared and reset to POR values by writing a '1' into the respective D0 bits. + ina209a.writeShuntVolPpk(0x01); // clear Shunt Voltage Positive Peak Register + ina209a.writeShuntVolNpk(0x01); + ina209a.writeBusVolMaxPk(0x01); + ina209a.writeBusVolMinPk(0x01); + ina209a.writePowerPk(0x01); + Serial.println(" Shunt Voltage Positive Peak "); + Serial.println(ina209a.readShuntVolPpk()); // mirrors highest voltage reading of the Shunt Voltage Register + Serial.println(" Shunt Voltage Negative Peak "); + Serial.println(ina209a.readShuntVolNpk()); + Serial.println(" Bus Voltage Maximum Peak "); + Serial.println(ina209a.readBusVolMaxPk()); + Serial.println(" Bus Voltage Minimum Peak "); + Serial.println(ina209a.readBusVolMinPk()); + Serial.println(" Power Peak "); + Serial.println(ina209a.readPowerPk()); // returns integer value Power Peak in mW (in this example = register value * Power LSB=2mW) + + // ----------------------- WARNING WATCHDOG REGISTERS ---------------------------------- + // These registers set warning limits that trigger flags in the Status Register and activate the Warning pin. + Serial.println(" Shunt Voltage Positive Warning "); + Serial.println(ina209a.readShuntVolPwrn()); + Serial.println(" Shunt Voltage Negative Warning "); + Serial.println(ina209a.readShuntVolNwrn()); + Serial.println(" Power Warning "); + Serial.println(ina209a.readPowerWrn()); + Serial.println(" Bus Over-Voltage Warning "); + Serial.println(ina209a.readBusOVwrn()); + Serial.println(" Bus Under-Voltage Warning "); + Serial.println(ina209a.readBusUVwrn()); + + // ----------------------- OVER-LIMIT/CRITICAL WATCHDOG REGISTERS ---------------------- + // These registers set the over-limit and critical DAC limits that trigger flags to be set in the Status Register and + // activate the Overlimit pin or the Critical pin. + Serial.println(" Power Over-Limit "); + Serial.println(ina209a.readPowerOL()); + Serial.println(" Bus Over-Voltage Over-Limit "); + Serial.println(ina209a.readBusOVOL()); + Serial.println(" Bus Under-Voltage Over-Limit "); + Serial.println(ina209a.readBusUVOL()); + Serial.println(" Critical Shunt Positive Voltage "); + Serial.println(ina209a.readCrShuntPV()); + Serial.println(" Critical Shunt Negative Voltage "); + Serial.println(ina209a.readCrShuntNV()); + +} diff --git a/lib/INA209/keywords.txt b/lib/INA209/keywords.txt new file mode 100644 index 0000000..9022cb9 --- /dev/null +++ b/lib/INA209/keywords.txt @@ -0,0 +1,42 @@ +INA209 KEYWORD1 +readCfgReg KEYWORD2 +writeCfgReg KEYWORD2 +statusReg KEYWORD2 +readSMBusCtrlReg KEYWORD2 +writeSMBusCtrlReg KEYWORD2 +shuntVol KEYWORD2 +busVol KEYWORD2 +power KEYWORD2 +current KEYWORD2 +readShuntVolPpk KEYWORD2 +writeShuntVolPpk KEYWORD2 +readShuntVolNpk KEYWORD2 +writeShuntVolNpk KEYWORD2 +readBusVolMaxPk KEYWORD2 +writeBusVolMaxPk KEYWORD2 +readBusVolMinPk KEYWORD2 +writeBusVolMinPk KEYWORD2 +readPowerPk KEYWORD2 +writePowerPk KEYWORD2 +readShuntVolPwrn KEYWORD2 +writeShuntVolPwrn KEYWORD2 +readShuntVolNwrn KEYWORD2 +writeShuntVolNwrn KEYWORD2 +readPowerWrn KEYWORD2 +writePowerWrn KEYWORD2 +readBusOVwrn KEYWORD2 +writeBusOVwrn KEYWORD2 +readBusUVwrn KEYWORD2 +writeBusUVwrn KEYWORD2 +readPowerOL KEYWORD2 +writePowerOL KEYWORD2 +readBusOVOL KEYWORD2 +writeBusOVOL KEYWORD2 +readBusUVOL KEYWORD2 +writeBusUVOL KEYWORD2 +readCrShuntPV KEYWORD2 +writeCrShuntPV KEYWORD2 +readCrShuntNV KEYWORD2 +writeCrShuntNV KEYWORD2 +readCal KEYWORD2 +writeCal KEYWORD2 \ No newline at end of file diff --git a/lib/README b/lib/README new file mode 100644 index 0000000..6debab1 --- /dev/null +++ b/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/lib/commandFunctions/commandFunctions.cpp b/lib/commandFunctions/commandFunctions.cpp new file mode 100644 index 0000000..00ff01a --- /dev/null +++ b/lib/commandFunctions/commandFunctions.cpp @@ -0,0 +1,95 @@ +/* These are the main functionalies and/or processes, they rely on the support + * functions (located in supportFunctions.cpp) to properally execute */ + +#include "commandFunctions.h" +#include "supportFunctions.h" +#include "testFun.h" + +//This tests the sensors and makes sure they are reading correctly +//This function can be depriciated to just call TEST() when needed. +void testFun() +{ + TEST(); //In testFun.cpp + return; +} + +//This will loop indefinately until there is something in UART +void standby() +{ + //Delay then return? + //In standby, auto try and detumble? Since this is the first mode... + return; +} + +//Starts rotation and checks that rotation actually occured +//This function will be changed later to support direction +//This function can probably be simplifed and have some things ran in supportFunctions.cpp, but good 'nuff for now. +void orient(const char *direction) +{ + ICM_20948_I2C *sensor_ptr1 = &IMU1; + ICM_20948_I2C *sensor_ptr2 = &IMU2; +//First ping values for IMU 1 + fixed5_3_t gyroZ1; +//Second ping values for IMU 1 + fixed5_3_t DIFFgyroZ1; +//First ping values for IMU 2 + fixed5_3_t gyroZ2; +//Second ping values for IMU 2 + fixed5_3_t DIFFgyroZ2; + + + //For now, check that satelite is currently stablized. If not, stablize then rotate. + //Copied from main.cpp/writeUART(): Get current rotation/speed of rotation + //To test if there is rotation, it will test the difference between 2 data points taken ~1 sec apart. + if (IMU1.dataReady() && IMU2.dataReady()) + { + IMU1.getAGMT(); // acquires data from sensor + IMU2.getAGMT(); // acquires data from sensor + +//Get data for first set of values + // extract data from IMU object + gyroZ1 = floatToFixed(sensor_ptr1->gyrZ()); + gyroZ2 = floatToFixed(sensor_ptr2->gyrZ()); + + //Copied from test/test.cpp + const int duration = 1000; // 1s + volatile long int t0 = millis(); + while(millis() - t0 < duration){/*do nothing*/} + +//After wait, grab the second set of values and calculate difference + IMU1.getAGMT(); // acquires data from sensor + IMU2.getAGMT(); // acquires data from sensor + + // extract data from IMU object + DIFFgyroZ1 = gyroZ1-(floatToFixed(sensor_ptr1->gyrZ())); + DIFFgyroZ2 = gyroZ2-(floatToFixed(sensor_ptr2->gyrZ())); + //gyro Z AXIS + + //Takes an average of the second set of data + fixed5_3_t Average = (DIFFgyroZ1+DIFFgyroZ2)/2; + + //0 would mean no rotation, anything other than 0 would be in some range of rotation (bigger the number, more rotation) + //We really only care about what's going on with the Z-axis, the others are a sanity check. + if(Average <= 1 && Average >= -1) //We probably can't get to a perfect 0, but a low rotation should be ok + { + //Start planned rotation here. Since we are just correcting for now, nothing more needs to be done; leave function. + return; + } + else //If here, there is some rotation occuring + { + //Rotate to stop rotation and call the function again after a select duration + DRV->run(FWD, 0.2*255); //20% TEMP-------- + + //IDEA: + //txt file that holds all of the previous data points of rotation (makes it easier to troubleshoot now, can move to array later) + //Do the math for rotation + + //If theres a negitive value, rotate forwards + //positive value, rotate backwards + //rotate + //call function again (loopies) + } + + return; + } +} diff --git a/lib/testFun/README.md b/lib/testFun/README.md new file mode 100644 index 0000000..2f4529d --- /dev/null +++ b/lib/testFun/README.md @@ -0,0 +1,2 @@ +# Test Library +This library contains the various system test functions for the ADCS System. These test functions should be run outside of the RTOS since they may include data collection and debug serial statements that will seriously mess with the RTOS scheduler. diff --git a/lib/testFun/test.cpp b/lib/testFun/test.cpp new file mode 100644 index 0000000..1f02f9c --- /dev/null +++ b/lib/testFun/test.cpp @@ -0,0 +1,228 @@ +#include +#include "DRV_10970.h" +#include "sensors.h" +#include "commandFunctions.h" +#include +#include + +DRV10970* DRV; +INA209* ina209; +ICM_20948_I2C IMU1; +ICM_20948_I2C IMU2; + +/* + * ADCS system test rig. Run to see test output on serial output in a loop. + * @author Garrett Wells + * @since 01/23/2022 + */ + +// Initialization functions, each should print to serial debug on success/failure +void init_test(void); // init ADCS systems and sensors +void initIMU_test(void); // init IMU +void initDRV_test(void); // init motor driver +void initINA_test(void); // init current monitor + +// Test functions, each should get input or send value to sensor or subsystem and then read/get feedback and print success/failure +void testIMU(void); // test IMU readings to make sure values are plausible +void testDRV_RAMP(void); // spin up in increments, and test ability to read wheel rpm +void testDRV_CONSTANT(void); // spin up in increments, and test ability to read wheel rpm +void testINA(void); // measure the draw of the system, should be non-zero + + +#ifdef TEST_H +/* + * Init for the tests + */ +void setup(){ + DRV = new DRV10970(DRV_FG, DRV_FR, DRV_BRKMOD, DRV_PWM, DRV_RD); + DRV->stop(); + // start serial debug + Serial.begin(115200); + while(!Serial){;} + + Serial.println("Ready to Test(1/0)?:"); + while(Serial.available() == 0){} + + int ans = Serial.parseInt(); + + init_test(); // init all ADCS systems + +} + +/* + * Run tests here to infinity + */ +void loop(){ + Serial.println("------ START TESTING SUBSYSTEMS ------"); + // Test IMU, values back should be close to zero if not moving + //testIMU(); + testDRV_RAMP(); + testDRV_CONSTANT(); + //testINA(); + Serial.println("------ END TESTING SUBSYSTEMS ------\n"); +} +#endif + +/* + * Init all systems here... + */ +void init_test(void){ + Serial.println("------ STARTING SYSTEM INIT ------"); + //initIMU_test(); + initDRV_test(); + //initINA_test(); + Serial.println("------ FINISHING SYSTEM INIT ------"); +} + +/* + * Init the IMU connection over the I2C interface + */ +void initIMU_test(void){ + /** + * Initialize I2C connection to IMU + * Clock: 400 kHz + * IMU address: 0x69 + */ + long int t0 = millis(); + SERCOM_I2C.begin(); + SERCOM_I2C.setClock(400000); + IMU1.begin(SERCOM_I2C, 0); + while (IMU1.status != ICM_20948_Stat_Ok); // wait for initialization to + long int cT = millis(); + Serial.print("INIT IMU [SUCCESS] in "); + Serial.print(cT - t0); + Serial.println(" ms"); +} + +/* + * Init the motor driver for the flywheel + */ +void initDRV_test(void){ + if(DRV_FG == 0 || DRV_FR == 0 || DRV_PWM == 0 || DRV_RD == 0){ + Serial.println("INIT DRV10970 [FAILED]\n\t invalid pinout"); + + }else { + long int t0 = millis(); + //DRV->stop(); + long int cT = millis(); + Serial.print("INIT DRV10970 [SUCCESS] in "); + Serial.print(cT - t0); + Serial.println(" ms"); + + } + } + +/* + * Init the INA209 current sensor for monitoring system draw + */ +void initINA_test(void){ + // TODO init INA209 with real values, defaults are for 32V system + long int t0 = millis(); + ina209 = new INA209(0x40); + ina209->writeCfgReg(14751); // default + ina209->writeCal(4096); + long int cT = millis(); + Serial.print("INIT INA209 [SUCCESS] in "); + Serial.print(cT - t0); + Serial.println(" ms"); +} + +/* + * Test the IMU, values should be close to zero but probably not zero if the unit is stationary + */ +void testIMU(void){ + Serial.println("\tIMU TEST"); + printScaledAGMT(&IMU1); + Serial.println(""); +} + +/* + * Test the DRV10979 motor driver + */ +void testDRV_RAMP(void){ + Serial.println("\tDRV10970 RAMP & RPM TEST"); + + // set LED on pin 13 HIGH + pinMode(13, OUTPUT); + digitalWrite(13, HIGH); + + const int duration = 1000; // 0.5s + volatile long int t0 = millis(); + long int currentTime; + double percentage = 0.1; + while(true){ + + currentTime = millis(); + if((currentTime - t0 > duration) && percentage < 1.0){ + // set duty cycle + Serial.print("\tDC = "); + Serial.println(percentage * 100); + DRV->run(FWD, percentage*255); + delay(2000); + // read rpm + int rpm_ticks = DRV->readRPM(false); + Serial.print("\t\tRPM ticks: "); + Serial.println(rpm_ticks); + // change percentage for next run + percentage += 0.1; + t0 = currentTime; + }else if(percentage >= 1.0){ + Serial.println("Ending Loop\n"); + break; + } + } + + Serial.println("\tstopping DRV10970"); + DRV->stop(); + Serial.println("\tDRV10970 stopped"); + delay(1000); +} + +void testDRV_CONSTANT(){ + Serial.println("\tDRV10970 CONSTANT OUTPUT TEST"); + + // set LED on pin 13 HIGH + pinMode(13, OUTPUT); + digitalWrite(13, HIGH); + // timing settings + const int duration = 10000; // 10s + const int poll_rt = 500; // poll frequency once every half second + long int t0_test = millis(); + long int t0_prt = t0_test; + long int currentTime; + + // start motor + DRV->run(FWD, 255*0.2); + + while(true){ + currentTime = millis(); + + if(currentTime - t0_prt > poll_rt){ + // read rpm + int rpm_ticks = DRV->readRPM(false); + Serial.print("\t\tRPM ticks: "); + Serial.println(rpm_ticks); + t0_prt = currentTime; + } + + if(currentTime - t0_test > duration){ + Serial.println("\t\tEnding Loop\n"); + break; + } + } + + Serial.println("\tstopping DRV10970"); + DRV->stop(); + Serial.println("\tDRV10970 stopped"); + //delay(1000); +} + +/* + * Test the INA209's ability to monitor the power draw of the system + */ +void testINA(void){ + Serial.println("\tINA209 TEST"); + Serial.print("\t\tINA209 current ("); + Serial.print(ina209->current()); + Serial.println(") Amps"); +} diff --git a/lib/testFun/test.h b/lib/testFun/test.h new file mode 100644 index 0000000..8438e9e --- /dev/null +++ b/lib/testFun/test.h @@ -0,0 +1,4 @@ +#ifndef TEST_H +#define TEST_H +// include this header to run test code +#endif diff --git a/platformio.ini b/platformio.ini new file mode 100644 index 0000000..4d4034c --- /dev/null +++ b/platformio.ini @@ -0,0 +1,16 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:sparkfun_samd51_thing_plus] +platform = atmelsam +board = sparkfun_samd51_thing_plus +framework = arduino +build_flags = -Iinclude/ +;lib_ldf_mode = deep diff --git a/src/comm.cpp b/src/comm.cpp new file mode 100644 index 0000000..276c6e7 --- /dev/null +++ b/src/comm.cpp @@ -0,0 +1,152 @@ +#include "comm.h" + +/* TEScommand METHODS ======================================================= */ + +TEScommand::TEScommand() +{ + clear(); +} + +void TEScommand::addByte(uint8_t b) +{ + _data[_bytes_received] = b; + _bytes_received++; + + if (_bytes_received >= COMMAND_LEN) + { + _full = true; + _bytes_received = 0; + } + else + { + _full = false; + } +} + +bool TEScommand::isFull() +{ + return _full; +} + +uint8_t TEScommand::getCommand() +{ + return _command; +} + +bool TEScommand::checkCRC() +{ + CRC16 crcGen; + crcGen.add(_data, COMMAND_LEN-2); + +#if 0 + char crc_str[8]; + sprintf(crc_str, "0x%02x", crcGen.getCRC()); + SERCOM_USB.write("TES CRC: "); + SERCOM_USB.write(crc_str); + SERCOM_USB.write("\r\n"); +#endif + + if (crcGen.getCRC() == _crc) + return true; + else + return false; +} + +void TEScommand::clear() +{ + for (int i = 0; i < COMMAND_LEN; i++) + _data[i] = 0; + + _bytes_received = 0; +} + +/* ADCSdata METHODS ========================================================= */ + +ADCSdata::ADCSdata() +{ + clear(); +} + +void ADCSdata::setStatus(uint8_t s) +{ + _status = s; +} + +void ADCSdata::setINAdata(float v, float i) +{ + _voltage = floatToFixed(v); + _current = (int8_t)(i / 10); +} + +void ADCSdata::setIMUdata(float mx, float my, float mz, float gx, float gy, float gz) +{ + _magX = (int8_t)mx; + _magY = (int8_t)my; + _magZ = (int8_t)mz; + + _gyroX = floatToFixed(gx); + _gyroY = floatToFixed(gy); + _gyroZ = floatToFixed(gz); +} + +void ADCSdata::computeCRC() +{ + CRC16 crcGen; + crcGen.add(_data, PACKET_LEN-2); + _crc = crcGen.getCRC(); + +#if 0 + char crc_str[8]; + sprintf(crc_str, "0x%02x", crcGen.getCRC()); + SERCOM_USB.write("CRC: "); + SERCOM_USB.write(crc_str); + SERCOM_USB.write("\r\n"); +#endif +} + +void ADCSdata::clear() +{ + for (int i = 0; i < PACKET_LEN; i++) + _data[i] = 0; +} + +void ADCSdata::send() +{ + SERCOM_UART.write((char*)_data, PACKET_LEN); +} + +/* HELPER FUNCTIONS ========================================================= */ + +/** + * @brief + * Converts a floating-point number to a fixed-point number with 5 bits for the + * integer part and 3 bits for the fraction part. Resulting data cannot be + * properly interpreted until converted back into a float. + * + * @param[in] f Float to convert + * + * @return Fixed-point conversion + */ +fixed5_3_t floatToFixed(float f) +{ + fixed5_3_t fix; + fix = (uint8_t)(f * (1 << 3)); + return fix; +} + +/** + * @brief + * Converts a fixed-point number with 5 integer bits and 3 fraction bits to a + * floating-point number. Resulting data can be properly interpreted with no + * extra conversions. + * + * @param[in] fix Fixed-point number to convert + * + * @return Float conversion + */ +float fixedToFloat(fixed5_3_t fix) +{ + float f; + f = ((float)fix) / (1 << 3); + return f; +} \ No newline at end of file diff --git a/src/commandFunctions.cpp b/src/commandFunctions.cpp new file mode 100644 index 0000000..14bda04 --- /dev/null +++ b/src/commandFunctions.cpp @@ -0,0 +1,114 @@ +/* These are the main functionalies and/or processes, they rely on the support + * functions (located in supportFunctions.cpp) to properally execute */ + +#include "commandFunctions.h" +#include "supportFunctions.h" + +extern ICM_20948_I2C IMU1; +#ifdef TWO_IMUS +extern ICM_20948_I2C IMU2; +#endif +extern DRV10970* DRV; + +//This tests the sensors and makes sure they are reading correctly +void testFun() +{ + //Call test/test.cpp? + return; +} + +//This will loop indefinately until there is something in UART +void standby() +{ + //Delay then return? + //In standby, auto try and detumble? Since this is the first mode... + return; +} + +//Starts rotation and checks that rotation actually occured +//This function will be changed later to support direction +void orient(const char *direction) +{ + ICM_20948_I2C *sensor_ptr = &IMU1; +//First ping values + int8_t magX; + int8_t magY; + int8_t magZ; + fixed5_3_t gyroX; + fixed5_3_t gyroY; + fixed5_3_t gyroZ; +//Second ping values + int8_t DIFFmagX; + int8_t DIFFmagY; + int8_t DIFFmagZ; + fixed5_3_t DIFFgyroX; + fixed5_3_t DIFFgyroY; + fixed5_3_t DIFFgyroZ; + + const int duration = 10000; // 10s + volatile long int t0 = millis(); + + + //For now, check that satelite is currently stablized. If not, stablize then rotate. + //Copied from main.cpp/writeUART(): Get current rotation/speed of rotation + //To test if there is rotation, it will test the difference between 2 data points taken ~1 sec apart. + if (IMU1.dataReady()) + { + IMU1.getAGMT(); // acquires data from sensor + +//Get data for first set of values + // extract data from IMU object + magX = (int8_t)sensor_ptr->magX(); + magY = (int8_t)sensor_ptr->magY(); + magZ = (int8_t)sensor_ptr->magZ(); + + gyroX = floatToFixed(sensor_ptr->gyrX()); + gyroY = floatToFixed(sensor_ptr->gyrY()); + gyroZ = floatToFixed(sensor_ptr->gyrZ()); + + //Copied from test/test.cpp + const int duration = 1000; // 1s + volatile long int t0 = millis(); + while(millis() - t0 < duration){/*do nothing*/} + +//After wait, grab the second set of values and calculate difference + IMU1.getAGMT(); // acquires data from sensor + + // extract data from IMU object + DIFFmagX = magX-((int8_t)sensor_ptr->magX()); + DIFFmagY = magY-((int8_t)sensor_ptr->magY()); + DIFFmagZ = magZ-((int8_t)sensor_ptr->magZ()); + + DIFFgyroX = gyroX-(floatToFixed(sensor_ptr->gyrX())); + DIFFgyroY = gyroY-(floatToFixed(sensor_ptr->gyrY())); + DIFFgyroZ = gyroZ-(floatToFixed(sensor_ptr->gyrZ())); + //gyro Z AXIS + + //0 would mean no rotation, anything other than 0 would be a range of rotation (bigger the number, more rotation) + //We really only care about what's going on with the Z-axis, the others are a sanity check. + if(DIFFgyroZ != 0) + { + //Start planned rotation here + return; + } + else //If here, there is some rotation occuring + { + //Rotate to stop rotation and call the function again after a select duration + if(DIFFgyroZ > 0) //Positive spin + { + DRV->run(FWD, 0.1*255); // start at 10% + while(millis() - t0 < duration){/*do nothing*/} + DRV->stop(); + } + else //Negitive spin + { + DRV->run(FWD, 0.1*255); // start at 10% + while(millis() - t0 < duration){/*do nothing*/} + DRV->stop(); + } + orient(direction); //Call again + } + + } + return;//Probably print error here.. (If here, IMU's were not ready) +} diff --git a/src/main.cpp b/src/main.cpp new file mode 100644 index 0000000..f62c900 --- /dev/null +++ b/src/main.cpp @@ -0,0 +1,394 @@ +// Our own headers +#include "comm.h" +#include "sensors.h" +#include "supportFunctions.h" +#include "commandFunctions.h" +#include "DRV_10970.h" +#include "validation_tests.h" + +// only include this if test functions are desired +//#include + +// Arduino library headers +#include "INA209.h" +#include "ICM_20948.h" +#include "FreeRTOS_SAMD51.h" +// Standard C/C++ library headers +#include + +// if defined, enables debug print statements over USB to the serial monitor +#define DEBUG + +/* NON-RTOS GLOBAL VARIABLES ================================================ */ + +/** + * @brief + * IMU objects, attached to IMUs. Used to read data from IMUs. + */ +ICM_20948_I2C IMU1; +#ifdef TWO_IMUS +ICM_20948_I2C IMU2; +#endif + +// INA209 object +INA209 ina209(0x40); + +// DRV10970 object +DRV10970 flywhl; + +/* RTOS GLOBAL VARIABLES ==================================================== */ + +/** + * @brief + * FreeRTOS queue that stores the current mode of the ADCS. + * Possible values: + * MODE_STANDBY (0) + * MODE_TEST (1) + */ +QueueHandle_t modeQ; + +/* HELPER FUNCTIONS ========================================================= */ + +void init_hardware(void); +void init_PWM_50kHz(void); // set PWM output on a pin to 50kHz instead of default +void init_sensors(void); +void init_rtos_architecture(void); + +/* RTOS TASK DECLARATIONS =================================================== */ + +static void readUART(void *pvParameters); +static void writeUART(void *pvParameters); + +/* "MAIN" =================================================================== */ + +/** + * @brief + * Since main is already defined by the Arduino framework, we will use the + * setup function as if it were main. Since setup runs only once, it + * essentially behaves the same as main. + */ +int main(void) +{ + #ifdef DEBUG + /** + * Initialize USB connection to computer. Used to print debug messages. + * Baud rate: 115200 + * Data bits: 8 + * Parity: none + */ + SERCOM_USB.begin(115200); + while (!SERCOM_USB); // wait for initialization to complete + SERCOM_USB.write("USB interface initialized\r\n"); + #endif + + /** + * Initialize UART connection to satellite + * Baud rate: 115200 + * Data bits: 8 + * Parity: odd (1 bit) + */ + SERCOM_UART.begin(115200, SERIAL_8O1); + while (!SERCOM_UART); // wait for initialization to complete + #ifdef DEBUG + SERCOM_USB.write("UART interface initialized\r\n"); + #endif + + /** + * Initialize I2C network + * Clock: 400 kHz + */ + SERCOM_I2C.begin(); + SERCOM_I2C.setClock(400000); + + init_hardware(); // setup gpio pins + //init_PWM_50kHz(); + init_sensors(); // init the sensor interfaces + init_rtos_architecture(); // create rtos tasks and stuff + + // initialization completed, notify satellite + ADCSdata data_packet; + data_packet.setStatus(STATUS_HELLO); + data_packet.computeCRC(); + data_packet.send(); + + vTaskStartScheduler(); // start the RTOS + + // should never be reached if everything goes right + while (1) + { + data_packet.setStatus(STATUS_ADCS_ERROR); + data_packet.computeCRC(); + data_packet.send(); + vTaskDelay(1000 / portTICK_PERIOD_MS); + } + return 0; +} + +/* + * Loop is defined as the Idle Task Function for this port of FreeRTOS and must be defined + * NOTE: + * - USB noted to interrupt from sleep here... https://forum.arduino.cc/t/standby-sleep-mode-on-samd51/576584/6 + * - ALSO... this doesn't turn off pins if they are set high, state is saved + */ +void loop(){ + /* SAMD51 USBCore.cpp sets enable bit during sleep standby mode so USB needs to be disabled if in DEBUG*/ + #ifdef DEBUG + USB->HOST.CTRLA.reg &= ~USB_CTRLA_ENABLE; // disable USB in standby sleep mode... + #endif + // SLEEPRDY bit must be set to sleep + if(PM_INTFLAG_SLEEPRDY) + __WFI(); // enter low power mode when running Idle task to enter low power mode + + return; +} + + +/* Initialize all the GPIO pins and the builtin LED */ +void init_hardware(void){ + Serial.println("INIT HARDWARE\n"); + // configure power manager (PM) to enter STANDBY mode on _WFI() + PM->SLEEPCFG.bit.SLEEPMODE = 0x4; + //while(PM->SLEEPCFG.bit.SLEEPMODE != 0x4); // wait for register to set, cannot sleep + while(!PM_INTFLAG_SLEEPRDY); // SLEEPRDY flag must be set before __WFI() + + // enable LED + pinMode(LED_BUILTIN, OUTPUT); + digitalWrite(LED_BUILTIN, HIGH); + + pinMode(9, OUTPUT); + digitalWrite(9, HIGH); + + pinMode(10, OUTPUT); + analogWrite(10, 127); + +} + +/* + * Set the motor driver PWM pin to output @ 50kHz instead of... its default + * Code from: https://forum.arduino.cc/t/metro-m4-express-atsamd51-pwm-frequency-and-resolution/566491/2 + */ +void init_PWM_50kHz(void){ + // Set up the generic clock (GCLK7) to clock timer TCC0 + GCLK->GENCTRL[7].reg = GCLK_GENCTRL_DIV(1) | // Divide the 48MHz clock source by divisor 1: 48MHz/1 = 48MHz + GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW + GCLK_GENCTRL_GENEN | // Enable GCLK7 + GCLK_GENCTRL_SRC_DFLL; // Select 48MHz DFLL clock source + //GCLK_GENCTRL_SRC_DPLL1; // Select 100MHz DPLL clock source + //GCLK_GENCTRL_SRC_DPLL0; // Select 120MHz DPLL clock source + while (GCLK->SYNCBUSY.bit.GENCTRL7); // Wait for synchronization + + GCLK->PCHCTRL[25].reg = GCLK_PCHCTRL_CHEN | // Enable the TCC0 peripheral channel + GCLK_PCHCTRL_GEN_GCLK7; // Connect generic clock 7 to TCC0 + + // Enable the peripheral multiplexer on pin D7 + PORT->Group[g_APinDescription[DRV_PWM].ulPort].PINCFG[g_APinDescription[DRV_PWM].ulPin].bit.PMUXEN = 1; + + // Set the D7 (PORT_PB12) peripheral multiplexer to peripheral (even port number) E(6): TCC0, Channel 0 + PORT->Group[g_APinDescription[DRV_PWM].ulPort].PMUX[g_APinDescription[DRV_PWM].ulPin >> 1].reg |= PORT_PMUX_PMUXE(6); + + TCC0->CTRLA.reg = TC_CTRLA_PRESCALER_DIV8 | // Set prescaler to 8, 48MHz/8 = 6MHz + TC_CTRLA_PRESCSYNC_PRESC; // Set the reset/reload to trigger on prescaler clock + + TCC0->WAVE.reg = TC_WAVE_WAVEGEN_NPWM; // Set-up TCC0 timer for Normal (single slope) PWM mode (NPWM) + while (TCC0->SYNCBUSY.bit.WAVE) // Wait for synchronization + +// TCC0->PER.reg = 479; // Set-up the PER (period) register 100kHz PWM + TCC0->PER.reg = 959; // Set-up the PER (period) register 50kHz PWM + while (TCC0->SYNCBUSY.bit.PER); // Wait for synchronization + + TCC0->CC[0].reg = 478; // Set-up the CC (counter compare), channel 0 register for 50% duty-cycle + while (TCC0->SYNCBUSY.bit.CC0); // Wait for synchronization + + TCC0->CTRLA.bit.ENABLE = 1; // Enable timer TCC0 + while (TCC0->SYNCBUSY.bit.ENABLE); // Wait for synchronization +} + + +/* Setup the sensor objects */ +void init_sensors(void){ + /** + * Initialize first IMU + * Address: 0x69 or 0x68 + */ + IMU1.begin(SERCOM_I2C, AD0_VAL); + while (IMU1.status != ICM_20948_Stat_Ok); // wait for initialization to + // complete + #ifdef DEBUG + SERCOM_USB.write("IMU1 initialized\r\n"); + #endif + + #ifdef TWO_IMUS + /** + * Initialize second IMU + * Address: 0x68 or 0x69 + */ + IMU2.begin(SERCOM_I2C, AD0_VAL^1); // initialize other IMU with opposite + // value for bit 0 + while (IMU2.status != ICM_20948_Stat_Ok); // wait for initialization to + // complete + #ifdef DEBUG + SERCOM_USB.write("IMU2 initialized\r\n"); + #endif + #endif + + /** + * Write default settings to INA209 + * Reset: no + // * Bus voltage range: 32V + * PGA gain: /8 + * PGA range: +-320mV + * ADC resolution: 12 bits + * ADC conversion time: 532us + * Mode: shunt and bus, continuous + */ + ina209.writeCfgReg(0x399f); + + /** + * Calibrate INA209 + * Current LSB: 100uA + */ + ina209.writeCal(0x7fff); + + #ifdef DEBUG + SERCOM_USB.write("INA209 initialized\r\n"); + #endif + +} + +/* Create all RTOS tasks, queues, semaphores, etc */ +void init_rtos_architecture(void){ + // Create a counting semaphore with a maximum value of 1 and an initial + // value of 0. Starts ADCS in standby mode. + modeQ = xQueueCreate(1, sizeof(uint8_t)); + uint8_t mode = MODE_TEST; + xQueueSend(modeQ, (void*)&mode, (TickType_t)0); + + //xTaskCreate(readUART, "Read UART", 2048, NULL, 1, NULL); + xTaskCreate(writeUART, "Write UART", 2048, NULL, 1, NULL); + //xTaskCreate(basic_motion1, "BASIC MOTION TEST", 256, NULL, 1, NULL); + + #ifdef DEBUG + SERCOM_USB.write("Tasks created\r\n"); + #endif +} + +/* RTOS TASK DEFINITIONS ==================================================== */ + +/** + * @brief + * Polls the UART module for data. Processes data one byte at a time if the + * module reports that data is ready to be received. + * + * @param[in] pvParameters Unused but required by FreeRTOS. Program will not + * compile without this parameter. When a task is instantiated from this + * function, a set of initialization arguments or NULL is passed in as + * pvParameters, so pvParameters must be declared even if it is not used. + * + * @return None + * + * TODO: Remove polling and invoke this task using an interrupt instead. + */ +static void readUART(void *pvParameters) +{ + TEScommand cmd_packet; + ADCSdata response; + uint8_t mode; + + #ifdef DEBUG + char cmd_str[8]; // used to print command value to serial monitor + #endif + + while (1) + { + if (SERCOM_UART.available()) // at least one byte is in the UART + { // receive buffer + + // copy one byte out of UART receive buffer + cmd_packet.addByte((uint8_t)SERCOM_UART.read()); + + if (cmd_packet.isFull()) // full command packet received + { + if (cmd_packet.checkCRC()) + { + // process command if CRC is valid + if (cmd_packet.getCommand() == CMD_TEST) + mode = MODE_TEST; + + if (cmd_packet.getCommand() == CMD_STANDBY) + mode = MODE_STANDBY; + } + else + { + // send error message if CRC is not valid + response.setStatus(STATUS_COMM_ERROR); + response.computeCRC(); + response.send(); + } + + xQueueOverwrite(modeQ, (void*)&mode); // enter specified mode + + #ifdef DEBUG + // convert int to string for USB monitoring + sprintf(cmd_str, "0x%02x", cmd_packet.getCommand()); + + // print command value to USB + SERCOM_USB.print("Command received: "); + SERCOM_USB.print(cmd_str); + SERCOM_USB.print("\r\n"); + + if (cmd_packet.getCommand() == CMD_TEST) + SERCOM_USB.print("Entering test mode\r\n"); + + if (cmd_packet.getCommand() == CMD_STANDBY) + SERCOM_USB.print("Entering standby mode\r\n"); + #endif + } + } + + // vTaskDelay(1000 / portTICK_PERIOD_MS); + } +} + +/** + * @brief + * Reads magnetometer and gyroscope values from IMU and writes them to UART + * every 0.5 seconds while ADCS is in test mode. + * + * @param[in] pvParameters Unused but required by FreeRTOS. Program will not + * compile without this parameter. When a task is instantiated from this + * function, a set of initialization arguments or NULL is passed in as + * pvParameters, so pvParameters must be declared even if it is not used. + * + * @return None + */ +static void writeUART(void *pvParameters) +{ + uint8_t mode; + ADCSdata data_packet; + + #ifdef DEBUG + char mode_str[8]; + #endif + + while (1) + { + xQueuePeek(modeQ, (void*)&mode, (TickType_t)0); + + if (mode == MODE_TEST) + { + data_packet.setStatus(STATUS_OK); + readIMU(data_packet); + readINA(data_packet); + data_packet.computeCRC(); + data_packet.send(); // send to TES + #ifdef DEBUG + // SERCOM_USB.write("Wrote to UART\r\n"); + // printScaledAGMT(&IMU1); + #endif + + data_packet.clear(); + } + + vTaskDelay(1000 / portTICK_PERIOD_MS); + } +} diff --git a/src/sensors.cpp b/src/sensors.cpp new file mode 100644 index 0000000..05154ed --- /dev/null +++ b/src/sensors.cpp @@ -0,0 +1,247 @@ +#include "sensors.h" + +extern ICM_20948_I2C IMU1; +#ifdef TWO_IMUS +extern ICM_20948_I2C IMU2; +#endif + +extern INA209 ina209; + +void readIMU(ADCSdata &data_packet) +{ + ICM_20948_I2C *sensor_ptr1 = &IMU1; // IMU data can only be accessed through + // a pointer +#ifdef TWO_IMUS + ICM_20948_I2C *sensor_ptr2 = &IMU2; // IMU data can only be accessed through + // a pointer +#endif + + float mx, my, mz, gx, gy, gz; + + if (IMU1.dataReady()) + IMU1.getAGMT(); // acquires data from sensor + +#ifdef TWO_IMUS + if (IMU2.dataReady()) + IMU2.getAGMT(); +#endif + +#ifdef TWO_IMUS + // extract data from IMU object + mx = (sensor_ptr1->magY() + sensor_ptr2->magY()) / 2; + my = (sensor_ptr1->magX() + sensor_ptr2->magX()) / 2; + mz = (sensor_ptr1->magZ() + sensor_ptr2->magZ()) / -2; + + gx = (sensor_ptr1->gyrY() + sensor_ptr2->gyrY()) / 2; + gy = (sensor_ptr1->gyrX() + sensor_ptr2->gyrX()) / 2; + gz = (sensor_ptr1->gyrZ() + sensor_ptr2->gyrZ()) / -2; +#else + mx = sensor_ptr1->magY(); + my = sensor_ptr1->magX(); + mz = sensor_ptr1->magZ() * -1; + + gx = sensor_ptr1->gyrY(); + gy = sensor_ptr1->gyrX(); + gz = sensor_ptr1->gyrZ() * -1; +#endif + + data_packet.setIMUdata(mx, my, mz, gx, gy, gz); +} + +void readINA(ADCSdata &data_packet) +{ + float voltage; + float current; + + int v_raw; + int i_raw; + + v_raw = ina209.busVol(); + i_raw = ina209.current(); + + voltage = v_raw / 1000; + current = i_raw / 10; + + data_packet.setINAdata(voltage, current); + + char debug_str[32]; + sprintf(debug_str, "%d", v_raw); + SERCOM_USB.write("Bus voltage: "); + SERCOM_USB.write(debug_str); + SERCOM_USB.write(" mV\r\n"); + sprintf(debug_str, "%d", i_raw*100); + SERCOM_USB.write("Shunt current: "); + SERCOM_USB.write(debug_str); + SERCOM_USB.write(" uA\r\n"); +} + +void printPaddedInt16b(int16_t val) +{ + if (val > 0) + { + SERCOM_USB.print(" "); + if (val < 10000) + { + SERCOM_USB.print("0"); + } + if (val < 1000) + { + SERCOM_USB.print("0"); + } + if (val < 100) + { + SERCOM_USB.print("0"); + } + if (val < 10) + { + SERCOM_USB.print("0"); + } + } + else + { + SERCOM_USB.print("-"); + if (abs(val) < 10000) + { + SERCOM_USB.print("0"); + } + if (abs(val) < 1000) + { + SERCOM_USB.print("0"); + } + if (abs(val) < 100) + { + SERCOM_USB.print("0"); + } + if (abs(val) < 10) + { + SERCOM_USB.print("0"); + } + } + SERCOM_USB.print(abs(val)); +} + +/** + * @brief + * This function has something to do with printing IMU data over USB to the + * serial monitor. Other than that, I have no idea what it does. It came as part + * of the IMU demo code, and printScaledAGMT, which is used to validate data + * transmissions, relies on this function. + * + * @param[in] agmt An instance of the IMU data object + * + * @return None + */ +void printRawAGMT(ICM_20948_AGMT_t agmt) +{ + SERCOM_USB.print("RAW. Acc [ "); + printPaddedInt16b(agmt.acc.axes.x); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.acc.axes.y); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.acc.axes.z); + SERCOM_USB.print(" ], Gyr [ "); + printPaddedInt16b(agmt.gyr.axes.x); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.gyr.axes.y); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.gyr.axes.z); + SERCOM_USB.print(" ], Mag [ "); + printPaddedInt16b(agmt.mag.axes.x); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.mag.axes.y); + SERCOM_USB.print(", "); + printPaddedInt16b(agmt.mag.axes.z); + SERCOM_USB.print(" ], Tmp [ "); + printPaddedInt16b(agmt.tmp.val); + SERCOM_USB.print(" ]"); + SERCOM_USB.println(); +} + +/** + * @brief + * This function has something to do with printing IMU data over USB to the + * serial monitor. Other than that, I have no idea what it does. It came as part + * of the IMU demo code, and printScaledAGMT, which is used to validate data + * transmissions, relies on this function. + * + * @param[in] val Value to print + * @param[in] leading Number of digits left of the decimal + * @param[in] decimals Number of digits right of the decimal + * + * @return None + */ +void printFormattedFloat(float val, uint8_t leading, uint8_t decimals) +{ + float aval = abs(val); + if (val < 0) + { + SERCOM_USB.print("-"); + } + else + { + SERCOM_USB.print(" "); + } + for (uint8_t indi = 0; indi < leading; indi++) + { + uint32_t tenpow = 0; + if (indi < (leading - 1)) + { + tenpow = 1; + } + for (uint8_t c = 0; c < (leading - 1 - indi); c++) + { + tenpow *= 10; + } + if (aval < tenpow) + { + SERCOM_USB.print("0"); + } + else + { + break; + } + } + if (val < 0) + { + SERCOM_USB.print(-val, decimals); + } + else + { + SERCOM_USB.print(val, decimals); + } +} + +/** + * @brief + * Prints IMU data over USB to the serial monitor. Converts raw data to a form + * that is readable by humans. Came as part of the IMU demo code. + * + * @param[in] sensor Pointer to IMU object + * + * @return None + */ +void printScaledAGMT(ICM_20948_I2C *sensor) +{ + SERCOM_USB.print("Scaled. Acc (mg) [ "); + printFormattedFloat(sensor->accX(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->accY(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->accZ(), 5, 2); + SERCOM_USB.print(" ], Gyr (DPS) [ "); + printFormattedFloat(sensor->gyrX(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->gyrY(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->gyrZ(), 5, 2); + SERCOM_USB.print(" ], Mag (uT) [ "); + printFormattedFloat(sensor->magX(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->magY(), 5, 2); + SERCOM_USB.print(", "); + printFormattedFloat(sensor->magZ(), 5, 2); + SERCOM_USB.print(" ], Tmp (C) [ "); + printFormattedFloat(sensor->temp(), 5, 2); + SERCOM_USB.print(" ]"); + SERCOM_USB.println(); +} \ No newline at end of file diff --git a/src/supportFunctions.cpp b/src/supportFunctions.cpp new file mode 100644 index 0000000..c7192be --- /dev/null +++ b/src/supportFunctions.cpp @@ -0,0 +1,63 @@ +/* These are functions that support the main command functions in one way + * or another they are called upon in the commandFunctions.cpp file */ + +#include "supportFunctions.h" +#include "commandFunctions.h" +#include +#include "comm.h" +#include + +//Parses cmd and calls appropriate function +void doCmd(char *cmd) +{ + if (cmd[0] == 0xa0) //Binary: 10100000 + { + testFun(); + } + else if (cmd[0] == 0xc0) //Binary: 11000000 + { + standby(); + } + //For now, the direction doesn't matter, but it's set up for later + else if (cmd[0] == 0xe0) //Binary: 11100000 + { + orient("X+"); + } + else if (cmd[0] == 0xe1) //Binary: 11100001 + { + orient("Y+"); + } + else if (cmd[0] == 0xe2) //Binary: 11100010 + { + orient("X-"); + } + else if (cmd[0] == 0xe3) //Binary: 11100011 + { + orient("Y-"); + } + return; +} + +//Reads all sensor output and compiles everything into the data array +/* WIP: I am unsure what data type data should be (prob int or float?).. + * I know it should be an array -Kristie */ +void getData(int *data) +{ + return; +} + +/* WIP: This will use the same data from function above, sends out to main + * satellite system */ +void sendToSystem(int *data) +{ + return; +} + +//Runs motors for a certain number of rotations +/* WIP: This function will need to take a rotation value (assuming int type) + * from orient and then rotate the motors that amount */ +void startRotation(int rotations) +{ + return; +} + diff --git a/src/validation_tests.cpp b/src/validation_tests.cpp new file mode 100644 index 0000000..05d646f --- /dev/null +++ b/src/validation_tests.cpp @@ -0,0 +1,31 @@ +/* + * These are the tests used to validate the correct operation of our system. + */ + +#include "validation_tests.h" + +/* + * Assume start from start, then begin increasing flywheel RPM until the system begins to spin. + * RULES: + * 1. check the IMU every loop and if the rotation rate is above MAX_TEST_SPD, stop revving + * 2. RPM only go up if some input is received... + */ +void basic_motion1(void* pvParameters){ + const int pwm_sig = 255 * 0.05; // 5% + const int MAX_TEST_SPD = 10; + + const TickType_t FREQ = 1000 / portTICK_PERIOD_MS; + + while(true){ + float rot_vel_z = IMU1.gyrZ(); + + Serial.write("USB interface initialized\r\n"); + + if( rot_vel_z < MAX_TEST_SPD){ + flywhl.run(FWD, pwm_sig); + } + + vTaskDelay(FREQ); + } + +} diff --git a/test/README b/test/README new file mode 100644 index 0000000..b94d089 --- /dev/null +++ b/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Unit Testing and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/page/plus/unit-testing.html diff --git a/test/test_motor/README.md b/test/test_motor/README.md new file mode 100644 index 0000000..4015f66 --- /dev/null +++ b/test/test_motor/README.md @@ -0,0 +1,2 @@ +# Motor Tests +Theses tests provide the fastest way to verify hardware performance matches minimum expectations for safe operation. diff --git a/test/test_motor/test.cpp b/test/test_motor/test.cpp new file mode 100644 index 0000000..d4d5d75 --- /dev/null +++ b/test/test_motor/test.cpp @@ -0,0 +1,48 @@ +#include +#include + +//#include "C:\Users\deepg\OneDrive\Documents\U_of_I\2021-22_UofI\CS480\ADCS\adcs\lib\DRV10970\src\DRV_10970.h" +#include + +DRV10970* DRV; + +// Make sure that when we init the DRV10970 it does not start spinning +void test_default_state(void){ + DRV = new DRV10970(DRV_FG, DRV_FR, DRV_BRKMOD, DRV_PWM, DRV_RD); + TEST_ASSERT_EQUAL(0, DRV->readRPM(false)); +} + +// Make sure the pins are initialized to valid values +void test_pin_values(void){ + TEST_ASSERT(DRV_FG != 0 && DRV_FR != 0 && DRV_BRKMOD == 0 && DRV_PWM != 0 && DRV_RD != 0); +} + +// Cycle from 0 to 100% DC and check that frequency pin is outputting +void test_frequency(void){ + float step_size = 0.05; + float percentage_output = 0; + int count; + + while(percentage_output <= 1){ + DRV->run(FWD, percentage_output * 255); + percentage_output += step_size; + delay(1000); + count = DRV->readRPM(false); + } + + DRV->stop(); + TEST_ASSERT(count > 0); +} + +void setup(void){ + // start serial debug + delay(2000); + UNITY_BEGIN(); + RUN_TEST(test_pin_values); + RUN_TEST(test_default_state); + RUN_TEST(test_frequency); +} + +void loop(){ + UNITY_END(); +}