From 70ca58f575410212567858353f2577c1c1073b4a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Davide=20Tom=C3=A9?= Date: Wed, 19 Oct 2022 16:30:30 +0200 Subject: [PATCH] add strain2c (#313) Co-authored-by: davidetome Co-authored-by: marco.accame --- .../v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h | 10 +- .../v2/proj/ems4rd.diagnostic2ready.uvoptx | 2 +- .../v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h | 10 +- .../v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h | 10 +- .../bootloader/proj/mtb4-bootloader-v6.uvoptx | 6 +- .../proj/mtb4-bootloader-v6.uvprojx | 22 +- .../mtb4c/application/src/main-appcan.cpp | 2 +- .../strain2c/application/bin/.placeholder.txt | 1 + .../cfg/stm32hal.startup.strain2.v190.s | 415 + .../strain2c/application/cfg/stm32hal_stg.h | 54 + .../proj/strain2c-application-v6.sct | 41 + .../proj/strain2c-application-v6.uvoptx | 1134 + .../proj/strain2c-application-v6.uvprojx | 848 + .../board/strain2c/application/src/adc2ft.cpp | 184 + .../board/strain2c/application/src/adc2ft.h | 136 + .../strain2c/application/src/adc2ft_data.cpp | 41 + .../application/src/bosch-driver/bno055.c | 17597 ++++++++++++++++ .../application/src/bosch-driver/bno055.h | 7973 +++++++ .../src/bosch-driver/bno055_support.c | 582 + .../src/main-strain2-application-legacy.cpp | 879 + .../src/main-strain2-application.cpp | 318 + .../strain2c/application/src/rtw_continuous.h | 131 + .../strain2c/application/src/rtw_solver.h | 267 + .../board/strain2c/application/src/rtwtypes.h | 106 + .../strain2c/bootloader/bin/.placeholder.txt | 1 + .../cfg/stm32hal.startup.strain2.v190.s | 415 + .../strain2c/bootloader/cfg/stm32hal_stg.h | 54 + .../proj/strain2c-bootloader-v6.sct | 40 + .../proj/strain2c-bootloader-v6.uvoptx | 741 + .../proj/strain2c-bootloader-v6.uvprojx | 773 + .../bootloader/src/main-bootloader.cpp | 36 + .../board/strain2c/bsp/embot_hw_bsp_config.h | 26 + .../strain2c/bsp/embot_hw_bsp_strain2c.cpp | 866 + .../bsp/embot_hw_bsp_strain2c_config.h | 39 + .../board/strain2c/test/bin/.placeholder.txt | 1 + .../test/cfg/stm32hal.startup.strain2.v190.s | 415 + .../board/strain2c/test/cfg/stm32hal_stg.h | 54 + .../strain2c/test/proj/strain2c-test-v6.sct | 40 + .../test/proj/strain2c-test-v6.uvoptx | 858 + .../test/proj/strain2c-test-v6.uvprojx | 798 + .../strain2c/test/proj/strain2c-test.sct | 38 + .../src/embot_code_bootloader-for-test.cpp | 573 + .../strain2c/test/src/main-bootloader.cpp | 36 + .../strain2c/test/strain2-canreal-tests.cspsl | 10 + .../updaterofbootloader/bin/.placeholder.txt | 1 + .../cfg/stm32hal.startup.strain2.v190.s | 415 + .../updaterofbootloader/cfg/stm32hal_stg.h | 54 + .../proj/strain2c-application-v6.sct | 41 + .../strain2c-updaterofbootloader-v6.uvoptx | 981 + .../strain2c-updaterofbootloader-v6.uvprojx | 1465 ++ .../src/main-updaterofbootloader-legacy.cpp | 179 + .../src/main-updaterofbootloader.cpp | 30 + .../embobj/plus/can/EOtheCANmapping.c | 18 +- .../arch-arm/embot/prot/can/embot_prot_can.h | 2 +- .../lowlevel/stm32hal/api/stm32hal_board.h | 28 + .../lowlevel/stm32hal/api/stm32hal_define.h | 16 + .../lowlevel/stm32hal/api/stm32hal_driver.h | 10 +- .../stm32hal/cubemx/strain2c/strain2c.ioc | 452 + .../stm32hal/lib/stm32hal.strain2c.v1B0.lib | Bin 0 -> 392986 bytes .../lowlevel/stm32hal/proj/stm32hal.l4.uvoptx | 319 + .../stm32hal/proj/stm32hal.l4.uvprojx | 7470 ++++++- .../src/board/strain2c/v1B0/inc/adc.h | 54 + .../src/board/strain2c/v1B0/inc/can.h | 52 + .../src/board/strain2c/v1B0/inc/dma.h | 52 + .../src/board/strain2c/v1B0/inc/gpio.h | 49 + .../src/board/strain2c/v1B0/inc/i2c.h | 60 + .../src/board/strain2c/v1B0/inc/main.h | 114 + .../v1B0/inc/removed.stm32l4xx_hal_conf.h | 482 + .../src/board/strain2c/v1B0/inc/rng.h | 52 + .../board/strain2c/v1B0/inc/stm32l4xx_it.h | 85 + .../src/board/strain2c/v1B0/inc/tim.h | 58 + .../src/board/strain2c/v1B0/inc/usart.h | 55 + .../src/board/strain2c/v1B0/src/adc.c | 239 + .../strain2c/v1B0/src/board_strain2c_v1B0.c | 260 + .../src/board/strain2c/v1B0/src/can.c | 125 + .../src/board/strain2c/v1B0/src/dma.c | 74 + .../src/board/strain2c/v1B0/src/gpio.c | 139 + .../src/board/strain2c/v1B0/src/i2c.c | 337 + .../board/strain2c/v1B0/src/removed.main.c | 204 + .../strain2c/v1B0/src/removed.stm32l4xx_it.c | 484 + .../v1B0/src/removed.system_stm32l4xx.c | 337 + .../src/board/strain2c/v1B0/src/rng.c | 96 + .../strain2c/v1B0/src/stm32l4xx_hal_msp.c | 81 + .../src/board/strain2c/v1B0/src/tim.c | 236 + .../src/board/strain2c/v1B0/src/usart.c | 262 + .../stm32hal/src/config/stm32hal_driver_cfg.h | 10 + .../stm32hal_driver_cfg_of_strain2c_v1B0.h | 533 + 87 files changed, 51937 insertions(+), 657 deletions(-) create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/bin/.placeholder.txt create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal.startup.strain2.v190.s create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal_stg.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.sct create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvoptx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvprojx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft_data.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.c create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055_support.c create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application-legacy.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_continuous.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_solver.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/application/src/rtwtypes.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/bin/.placeholder.txt create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal.startup.strain2.v190.s create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal_stg.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.sct create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvoptx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvprojx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bootloader/src/main-bootloader.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_config.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c_config.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/bin/.placeholder.txt create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal.startup.strain2.v190.s create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal_stg.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.sct create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvoptx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvprojx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test.sct create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/src/embot_code_bootloader-for-test.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/src/main-bootloader.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/test/strain2-canreal-tests.cspsl create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/bin/.placeholder.txt create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal.startup.strain2.v190.s create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal_stg.h create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-application-v6.sct create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvoptx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvprojx create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader-legacy.cpp create mode 100644 emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader.cpp create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/cubemx/strain2c/strain2c.ioc create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/lib/stm32hal.strain2c.v1B0.lib create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/adc.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/can.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/dma.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/gpio.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/i2c.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/main.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/removed.stm32l4xx_hal_conf.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/rng.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/stm32l4xx_it.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/tim.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/usart.h create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/adc.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/board_strain2c_v1B0.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/can.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/dma.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/gpio.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/i2c.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.main.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.stm32l4xx_it.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.system_stm32l4xx.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/rng.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/stm32l4xx_hal_msp.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/tim.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/usart.c create mode 100644 emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h diff --git a/emBODY/eBcode/arch-arm/board/ems004/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h b/emBODY/eBcode/arch-arm/board/ems004/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h index bd53aa2d99..b821cea06b 100644 --- a/emBODY/eBcode/arch-arm/board/ems004/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h +++ b/emBODY/eBcode/arch-arm/board/ems004/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h @@ -81,7 +81,7 @@ extern "C" { #define EOMTHEEMSAPPLCFG_VERSION_MAJOR (VERSION_MAJOR_OFFSET+3) // minor <0-255> // minor <0-255> -#define EOMTHEEMSAPPLCFG_VERSION_MINOR 55 +#define EOMTHEEMSAPPLCFG_VERSION_MINOR 56 // version @@ -89,13 +89,13 @@ extern "C" { // year <2010-2030> #define EOMTHEEMSAPPLCFG_BUILDDATE_YEAR 2022 // month <1-12> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 9 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 10 // day <1-31> -#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 23 +#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 18 // hour <0-23> -#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 13 +#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 15 // minute <0-59> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 28 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 07 // build date // Info diff --git a/emBODY/eBcode/arch-arm/board/ems004/appl/v2/proj/ems4rd.diagnostic2ready.uvoptx b/emBODY/eBcode/arch-arm/board/ems004/appl/v2/proj/ems4rd.diagnostic2ready.uvoptx index de6c25bbd7..750011d5d9 100644 --- a/emBODY/eBcode/arch-arm/board/ems004/appl/v2/proj/ems4rd.diagnostic2ready.uvoptx +++ b/emBODY/eBcode/arch-arm/board/ems004/appl/v2/proj/ems4rd.diagnostic2ready.uvoptx @@ -3770,7 +3770,7 @@ eo-protocol - 0 + 1 0 0 0 diff --git a/emBODY/eBcode/arch-arm/board/mc2plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h b/emBODY/eBcode/arch-arm/board/mc2plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h index 7a119edfca..50c11a99d4 100644 --- a/emBODY/eBcode/arch-arm/board/mc2plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h +++ b/emBODY/eBcode/arch-arm/board/mc2plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h @@ -75,20 +75,20 @@ extern "C" { #define EOMTHEEMSAPPLCFG_VERSION_MAJOR 3 // minor <0-255> // minor <0-255> -#define EOMTHEEMSAPPLCFG_VERSION_MINOR 39 +#define EOMTHEEMSAPPLCFG_VERSION_MINOR 40 // version // build date // year <2010-2030> #define EOMTHEEMSAPPLCFG_BUILDDATE_YEAR 2022 // month <1-12> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 9 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 10 // day <1-31> -#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 23 +#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 18 // hour <0-23> -#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 13 +#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 15 // minute <0-59> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 30 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 11 // build date // Info diff --git a/emBODY/eBcode/arch-arm/board/mc4plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h b/emBODY/eBcode/arch-arm/board/mc4plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h index 407d238a6a..eeffda994e 100644 --- a/emBODY/eBcode/arch-arm/board/mc4plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h +++ b/emBODY/eBcode/arch-arm/board/mc4plus/appl/v2/cfg/eoemsappl/EOMtheEMSapplCfg_cfg.h @@ -87,7 +87,7 @@ extern "C" { // minor <0-255> -#define EOMTHEEMSAPPLCFG_VERSION_MINOR 53 +#define EOMTHEEMSAPPLCFG_VERSION_MINOR 54 // version @@ -96,13 +96,13 @@ extern "C" { // year <2010-2030> #define EOMTHEEMSAPPLCFG_BUILDDATE_YEAR 2022 // month <1-12> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 9 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MONTH 10 // day <1-31> -#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 23 +#define EOMTHEEMSAPPLCFG_BUILDDATE_DAY 18 // hour <0-23> -#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 13 +#define EOMTHEEMSAPPLCFG_BUILDDATE_HOUR 15 // minute <0-59> -#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 29 +#define EOMTHEEMSAPPLCFG_BUILDDATE_MIN 14 // build date diff --git a/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvoptx b/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvoptx index d7f8e3a6fe..7ca11de69e 100644 --- a/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvoptx +++ b/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvoptx @@ -10,7 +10,7 @@ *.s*; *.src; *.a* *.obj; *.o *.lib - *.txt; *.h; *.inc + *.txt; *.h; *.inc; *.md *.plm *.cpp 0 @@ -328,7 +328,7 @@ 1 0 0 - 1 + 6 @@ -339,7 +339,7 @@ - BIN\ULP2CM3.DLL + STLink\ST-LINKIII-KEIL_SWO.dll diff --git a/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvprojx b/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvprojx index 9d0f16d3f6..63b91782da 100644 --- a/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvprojx +++ b/emBODY/eBcode/arch-arm/board/mtb4/bootloader/proj/mtb4-bootloader-v6.uvprojx @@ -16,8 +16,8 @@ STM32L433RCTx STMicroelectronics - Keil.STM32L4xx_DFP.2.5.0 - https://www.keil.com/pack/ + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ IRAM(0x20000000,0x0000C000) IRAM2(0x10000000,0x00004000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE @@ -186,6 +186,7 @@ 2 0 0 + 0 1 0 8 @@ -753,14 +754,14 @@ mtb4-btl-v190 0x4 ARM-ADS - 6140000::V6.14::ARMCLANG + 6180000::V6.18::ARMCLANG 1 STM32L433RCTx STMicroelectronics - Keil.STM32L4xx_DFP.2.5.0 - https://www.keil.com/pack/ + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ IRAM(0x20000000,0x0000C000) IRAM2(0x10000000,0x00004000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE @@ -929,6 +930,7 @@ 2 0 0 + 0 1 0 8 @@ -1521,8 +1523,8 @@ STM32L433RCTx STMicroelectronics - Keil.STM32L4xx_DFP.2.5.0 - https://www.keil.com/pack/ + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ IRAM(0x20000000,0x0000C000) IRAM2(0x10000000,0x00004000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE @@ -1691,6 +1693,7 @@ 2 0 0 + 0 1 0 8 @@ -2345,11 +2348,6 @@ <Project Info> - - - - - 0 1 diff --git a/emBODY/eBcode/arch-arm/board/mtb4c/application/src/main-appcan.cpp b/emBODY/eBcode/arch-arm/board/mtb4c/application/src/main-appcan.cpp index 568db91e8c..8b5bfb09de 100644 --- a/emBODY/eBcode/arch-arm/board/mtb4c/application/src/main-appcan.cpp +++ b/emBODY/eBcode/arch-arm/board/mtb4c/application/src/main-appcan.cpp @@ -18,7 +18,7 @@ constexpr embot::app::theCANboardInfo::applicationInfo applInfo embot::prot::can::versionOfAPPLICATION {20, 4, 5}, embot::prot::can::versionOfCANPROTOCOL {20, 0} #else - embot::prot::can::versionOfAPPLICATION {1, 4, 6}, + embot::prot::can::versionOfAPPLICATION {1, 4, 7}, embot::prot::can::versionOfCANPROTOCOL {2, 0} #endif }; diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/bin/.placeholder.txt b/emBODY/eBcode/arch-arm/board/strain2c/application/bin/.placeholder.txt new file mode 100644 index 0000000000..b0eb8200ba --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/bin/.placeholder.txt @@ -0,0 +1 @@ +.placeholder diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal.startup.strain2.v190.s b/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal.startup.strain2.v190.s new file mode 100644 index 0000000000..e9551a1aaf --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal.startup.strain2.v190.s @@ -0,0 +1,415 @@ +;********************** COPYRIGHT(c) 2017 STMicroelectronics ****************** +;* File Name : startup_stm32l443xx.s +;* Author : MCD Application Team +;* Version : V1.3.2 +;* Date : 16-June-2017 +;* Description : STM32L443xx Ultra Low Power devices vector table for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the Cortex-M4 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +;* +;* Redistribution and use in source and binary forms, with or without modification, +;* are permitted provided that the following conditions are met: +;* 1. Redistributions of source code must retain the above copyright notice, +;* this list of conditions and the following disclaimer. +;* 2. Redistributions in binary form must reproduce the above copyright notice, +;* this list of conditions and the following disclaimer in the documentation +;* and/or other materials provided with the distribution. +;* 3. Neither the name of STMicroelectronics nor the names of its contributors +;* may be used to endorse or promote products derived from this software +;* without specific prior written permission. +;* +;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +;* +;******************************************************************************* +; + +; in case of error from assembler, you surely forgot --cpreproc in menu asm-options/misc-controls +; or may also to include it into asm path in menu asm-options/include-paths +;#include "stm32hal_stg.h" + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Stack_Size EQU 0x00003000 +;Stack_Size EQU STM32HAL_STG_STACKSIZE + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Heap_Size EQU 0x00008000 +;Heap_Size EQU STM32HAL_STG_HEAPSIZE + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window WatchDog + DCD PVD_PVM_IRQHandler ; PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection + DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line + DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line + DCD FLASH_IRQHandler ; FLASH + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line0 + DCD EXTI1_IRQHandler ; EXTI Line1 + DCD EXTI2_IRQHandler ; EXTI Line2 + DCD EXTI3_IRQHandler ; EXTI Line3 + DCD EXTI4_IRQHandler ; EXTI Line4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; External Line[9:5]s + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; External Line[15:10] + DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SDMMC1_IRQHandler ; SDMMC1 + DCD 0 ; Reserved + DCD SPI3_IRQHandler ; SPI3 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel 1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel 2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel 3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel 4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel 5 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD COMP_IRQHandler ; COMP Interrupt + DCD LPTIM1_IRQHandler ; LP TIM1 interrupt + DCD LPTIM2_IRQHandler ; LP TIM2 interrupt + DCD USB_IRQHandler ; USB FS + DCD DMA2_Channel6_IRQHandler ; DMA2 Channel 6 + DCD DMA2_Channel7_IRQHandler ; DMA2 Channel 7 + DCD LPUART1_IRQHandler ; LP UART1 interrupt + DCD QUADSPI_IRQHandler ; Quad SPI global interrupt + DCD I2C3_EV_IRQHandler ; I2C3 event + DCD I2C3_ER_IRQHandler ; I2C3 error + DCD SAI1_IRQHandler ; Serial Audio Interface 1 global interrupt + DCD 0 ; Reserved + DCD SWPMI1_IRQHandler ; Serial Wire Interface 1 global interrupt + DCD TSC_IRQHandler ; Touch Sense Controller global interrupt + DCD LCD_IRQHandler ; LCD global interrupt + DCD AES_IRQHandler ; AES global interrupt + DCD RNG_IRQHandler ; RNG global interrupt + DCD FPU_IRQHandler ; FPU + DCD CRS_IRQHandler ; CRS interrupt + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_PVM_IRQHandler [WEAK] + EXPORT TAMP_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT SDMMC1_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT COMP_IRQHandler [WEAK] + EXPORT LPTIM1_IRQHandler [WEAK] + EXPORT LPTIM2_IRQHandler [WEAK] + EXPORT USB_IRQHandler [WEAK] + EXPORT DMA2_Channel6_IRQHandler [WEAK] + EXPORT DMA2_Channel7_IRQHandler [WEAK] + EXPORT LPUART1_IRQHandler [WEAK] + EXPORT QUADSPI_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT SAI1_IRQHandler [WEAK] + EXPORT SWPMI1_IRQHandler [WEAK] + EXPORT TSC_IRQHandler [WEAK] + EXPORT LCD_IRQHandler [WEAK] + EXPORT AES_IRQHandler [WEAK] + EXPORT RNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT CRS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_PVM_IRQHandler +TAMP_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTC_Alarm_IRQHandler +SDMMC1_IRQHandler +SPI3_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +COMP_IRQHandler +LPTIM1_IRQHandler +LPTIM2_IRQHandler +USB_IRQHandler +DMA2_Channel6_IRQHandler +DMA2_Channel7_IRQHandler +LPUART1_IRQHandler +QUADSPI_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +SAI1_IRQHandler +SWPMI1_IRQHandler +TSC_IRQHandler +LCD_IRQHandler +AES_IRQHandler +RNG_IRQHandler +FPU_IRQHandler +CRS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal_stg.h b/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal_stg.h new file mode 100644 index 0000000000..1f37a1155e --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/cfg/stm32hal_stg.h @@ -0,0 +1,54 @@ + + + +// - include guard ---------------------------------------------------------------------------------------------------- +#ifndef __STM32HAL_STG_H_ +#define __STM32HAL_STG_H_ + +#ifdef __cplusplus +extern "C" { +#endif + + + +// -------------------------------------------------------------------------------------------------------------------- +//-------- <<< Use Configuration Wizard in Context Menu >>> ----------------------------------------------------------- +// -------------------------------------------------------------------------------------------------------------------- + + +// STACK & HEAP +// It contains stack and heap size and some externally functions + +// stack size <0x0-0xFFFFFFFF:8> +// define how much stack you want. +#ifndef STM32HAL_STG_STACKSIZE + #define STM32HAL_STG_STACKSIZE 0x00003000 +#endif + +// heap size <0x0-0xFFFFFFFF:8> +// define how much heap you want. +#ifndef STM32HAL_STG_HEAPSIZE + #define STM32HAL_STG_HEAPSIZE 0x00008000 +#endif + +// SYS module + + + + +// -------------------------------------------------------------------------------------------------------------------- +//------------- <<< end of configuration section >>> ------------------------------------------------------------------ +// -------------------------------------------------------------------------------------------------------------------- + + + +#ifdef __cplusplus +} // closing brace for extern "C" +#endif + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.sct b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.sct new file mode 100644 index 0000000000..b38f3aa3d5 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.sct @@ -0,0 +1,41 @@ +;#! armcc -E +; the above must be on teh first line of teh scatter file ... + +; Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia +; Author: Marco Accame +; email: marco.accame@iit.it +; website: www.robotcub.org +; Permission is granted to copy, distribute, and/or modify this program +; under the terms of the GNU General Public License, version 2 or any +; later version published by the Free Software Foundation. +; +; A copy of the license can be found at +; http://www.robotcub.org/icub/license/gpl.txt +; +; This program is distributed in the hope that it will be useful, but +; WITHOUT ANY WARRANTY; without even the implied warranty of +; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General +; Public License for more details +; due to a bug in linker (in some older versions), you may need to put the whole path ... thus change it by hand +;#include "D:\#inhere\sdl\embedded\arm\embody\body\embenv\envcom\eEmemorymap.h" +;#include "..\..\cfg\eEmemorymap.h" + + +; flash starts from xx and its size is xxx +; 128k is: LR_IROM1 0x08020000 0x00020000 { ; load region size_region +; if we want to start at 80k, with size 256-80-4 and have a hole of 4k on top ... LR_IROM1 0x08014000 0x0002B000 { ; load region size_region +;LR_IROM1 0x08014000 0x0002B000 { ; load region size_region +LR_IROM1 0x08014000 0x0002B000 { ; load region size_region + ER_IROM1 0x08014000 0x0002B000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + RW_IRAM1 0x20000020 0xBFE0 { ; RW data + .ANY (+RW +ZI) + } +} + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvoptx b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvoptx new file mode 100644 index 0000000000..118ef0c2c8 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvoptx @@ -0,0 +1,1134 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc; *.md + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + strain2c-v1B0 + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 6 + + + + + + + + + + + STLink\ST-LINKIII-KEIL_SWO.dll + + + + 0 + ST-LINKIII-KEIL_SWO + -U -O206 -SF33000 -C0 -A0 -I0 -HNlocalhost -HP7184 -P1 -N00("ARM CoreSight SW-DP (ARM Core") -D00(2BA01477) -L00(0) -TO131090 -TC10000000 -TT10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256.FLM -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + UL2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ULP2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + (105=-1,-1,-1,-1,0) + + + + + + 0 + 1 + pImpl + + + 1 + 1 + replyinfo + + + 2 + 1 + replyinfo + + + 3 + 1 + dd + + + 4 + 1 + handleCalibTareQ15 + + + 5 + 1 + a + + + 6 + 1 + tmp[i] + + + + + 1 + 266 + a + 0 + + + + + 2 + 266 + runtimedata.adcvalueQ15vector.data + 0 + + + + + 3 + 265 + handleCalibTareQ15.data + 0 + + + + + 4 + 266 + tmpQ15vector.data + 0 + + + + 0 + + + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 0 + 0 + 2 + 33000000 + + + + + + main + 1 + 0 + 0 + 0 + + 1 + 1 + 8 + 0 + 0 + 0 + ../src/main-strain2-application.cpp + main-strain2-application.cpp + 0 + 0 + + + 1 + 2 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_basic.cpp + embot_app_skeleton_os_basic.cpp + 0 + 0 + + + 1 + 3 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_evthreadcan.cpp + embot_app_skeleton_os_evthreadcan.cpp + 0 + 0 + + + 1 + 4 + 8 + 0 + 0 + 0 + ..\src\adc2ft.cpp + adc2ft.cpp + 0 + 0 + + + 1 + 5 + 5 + 0 + 0 + 0 + ..\src\adc2ft.h + adc2ft.h + 0 + 0 + + + 1 + 6 + 8 + 0 + 0 + 0 + ..\src\adc2ft_data.cpp + adc2ft_data.cpp + 0 + 0 + + + 1 + 7 + 5 + 0 + 0 + 0 + ..\src\rtwtypes.h + rtwtypes.h + 0 + 0 + + + + + stm32hal + 1 + 0 + 0 + 0 + + 2 + 8 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + stm32hal.strain2c.v1B0.lib + 0 + 0 + + + + + stm32hal-config + 0 + 0 + 0 + 0 + + 3 + 9 + 2 + 0 + 0 + 0 + ..\cfg\stm32hal.startup.strain2.v190.s + stm32hal.startup.strain2.v190.s + 0 + 0 + + + + + rtos + 0 + 0 + 0 + 0 + + 4 + 10 + 4 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + osal.cm4.dbg.lib + 0 + 0 + + + 4 + 11 + 1 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\src\eventviewer.c + eventviewer.c + 0 + 0 + + + 4 + 12 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + cmsisos2.lib + 0 + 0 + + + + + embot + 0 + 0 + 0 + 0 + + 5 + 13 + 8 + 1 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + embot_core.cpp + 0 + 0 + + + 5 + 14 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + embot_core_binary.cpp + 0 + 0 + + + 5 + 15 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + embot_os.cpp + 0 + 0 + + + 5 + 16 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + embot_os_Thread.cpp + 0 + 0 + + + 5 + 17 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + embot_os_theCallbackManager.cpp + 0 + 0 + + + 5 + 18 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + embot_app_theJumper.cpp + 0 + 0 + + + 5 + 19 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + embot_os_theScheduler.cpp + 0 + 0 + + + 5 + 20 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + embot_os_theTimerManager.cpp + 0 + 0 + + + 5 + 21 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + embot_os_Timer.cpp + 0 + 0 + + + 5 + 22 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\tools\embot_tools.cpp + embot_tools.cpp + 0 + 0 + + + 5 + 23 + 8 + 1 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\dsp\embot_dsp.cpp + embot_dsp.cpp + 0 + 0 + + + 5 + 24 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + embot_app_theLEDmanager.cpp + 0 + 0 + + + 5 + 25 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_Action.cpp + embot_os_Action.cpp + 0 + 0 + + + 5 + 26 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_rtos.cpp + embot_os_rtos.cpp + 0 + 0 + + + + + embot-protocol + 0 + 0 + 0 + 0 + + 6 + 27 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + embot_prot_can.cpp + 0 + 0 + + + 6 + 28 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_skin_periodic.cpp + embot_prot_can_skin_periodic.cpp + 0 + 0 + + + 6 + 29 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_inertial_periodic.cpp + embot_prot_can_inertial_periodic.cpp + 0 + 0 + + + 6 + 30 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_motor_polling.cpp + embot_prot_can_motor_polling.cpp + 0 + 0 + + + 6 + 31 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_motor_periodic.cpp + embot_prot_can_motor_periodic.cpp + 0 + 0 + + + 6 + 32 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + embot_prot_can_bootloader.cpp + 0 + 0 + + + 6 + 33 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_analog_polling.cpp + embot_prot_can_analog_polling.cpp + 0 + 0 + + + 6 + 34 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_analog_periodic.cpp + embot_prot_can_analog_periodic.cpp + 0 + 0 + + + + + embot-parser + 0 + 0 + 0 + 0 + + 7 + 35 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserBasic.cpp + embot_app_application_theCANparserBasic.cpp + 0 + 0 + + + 7 + 36 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserSTRAIN.cpp + embot_app_application_theCANparserSTRAIN.cpp + 0 + 0 + + + 7 + 37 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserIMU.cpp + embot_app_application_theCANparserIMU.cpp + 0 + 0 + + + 7 + 38 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_application_theCANparserTHERMO.cpp + embot_app_application_theCANparserTHERMO.cpp + 0 + 0 + + + + + embot-application + 0 + 0 + 0 + 0 + + 8 + 39 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theApplication.cpp + embot_app_theApplication.cpp + 0 + 0 + + + 8 + 40 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + embot_app_theCANboardInfo.cpp + 0 + 0 + + + 8 + 41 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANtracer.cpp + embot_app_application_theCANtracer.cpp + 0 + 0 + + + 8 + 42 + 8 + 1 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theIMU.cpp + embot_app_application_theIMU.cpp + 0 + 0 + + + 8 + 43 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theSTRAIN.cpp + embot_app_application_theSTRAIN.cpp + 0 + 0 + + + 8 + 44 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_application_theTHERMO.cpp + embot_app_application_theTHERMO.cpp + 0 + 0 + + + 8 + 45 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_theStorage.cpp + embot_app_theStorage.cpp + 0 + 0 + + + + + embot-hw + 0 + 0 + 0 + 0 + + 9 + 46 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + embot_hw.cpp + 0 + 0 + + + 9 + 47 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + embot_hw_sys.cpp + 0 + 0 + + + 9 + 48 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + embot_hw_bsp.cpp + 0 + 0 + + + 9 + 49 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + embot_hw_FlashStorage.cpp + 0 + 0 + + + 9 + 50 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + embot_hw_FlashBurner.cpp + 0 + 0 + + + 9 + 51 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + embot_hw_can.cpp + 0 + 0 + + + 9 + 52 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + embot_hw_flash.cpp + 0 + 0 + + + 9 + 53 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_pga308.cpp + embot_hw_pga308.cpp + 0 + 0 + + + 9 + 54 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_adc.cpp + embot_hw_adc.cpp + 0 + 0 + + + 9 + 55 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_onewire.cpp + embot_hw_onewire.cpp + 0 + 0 + + + 9 + 56 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_timer.cpp + embot_hw_timer.cpp + 0 + 0 + + + 9 + 57 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_gpio.cpp + embot_hw_gpio.cpp + 0 + 0 + + + 9 + 58 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + embot_hw_led.cpp + 0 + 0 + + + 9 + 59 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_button.cpp + embot_hw_button.cpp + 0 + 0 + + + 9 + 60 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_si7051.cpp + embot_hw_si7051.cpp + 0 + 0 + + + 9 + 61 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_i2c.cpp + embot_hw_i2c.cpp + 0 + 0 + + + 9 + 62 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_bno055.cpp + embot_hw_bno055.cpp + 0 + 0 + + + + + embot-hw-lowlevel + 0 + 0 + 0 + 0 + + 10 + 63 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + embot_hw_lowlevel.cpp + 0 + 0 + + + + + embot::hw::bsp + 1 + 0 + 0 + 0 + + 11 + 64 + 8 + 0 + 0 + 0 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + embot_hw_bsp_strain2c.cpp + 0 + 0 + + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvprojx b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvprojx new file mode 100644 index 0000000000..60a5cc7171 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/proj/strain2c-application-v6.uvprojx @@ -0,0 +1,848 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + strain2c-v1B0 + 0x4 + ARM-ADS + 6180000::V6.18::ARMCLANG + 1 + + + STM32L452RCIx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x00020000) IRAM2(0x10000000,0x00008000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L452RCIx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L452RCIx$CMSIS\SVD\STM32L4x2.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + strain2c_v1B0 + 1 + 0 + 1 + 1 + 1 + .\lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\Obj\strain2c_v1B0.hex ..\bin\strain2c.v1B0.hex + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 0 + 0x10000000 + 0x8000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 8 + 1 + 1 + 1 + 0 + 0 + + -Wno-pragma-pack -Wno-deprecated-register + USE_STM32HAL STM32HAL_BOARD_STRAIN2C STM32HAL_DRIVER_V1B0 + + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\api;..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\api;..\..\..\..\..\..\eBcode\arch-arm\embobj\core\exec\multitask-;..\..\..\..\..\..\..\..\icub-firmware-shared\eth\embobj\core\core-;..\..\..\..\..\..\eBcode\arch-arm\libs\lowlevel\stm32hal\api;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\..\..\eBcode\arch-arm\embot\app;..\..\..\..\..\..\eBcode\arch-arm\embot\i2h;..\..\..\..\..\..\eBcode\arch-arm\embot\hw;..\..\..\..\..\..\eBcode\arch-arm\embot\os;..\..\..\..\..\..\eBcode\arch-arm\embot;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\embot\app\dsp;..\..\..\..\..\..\..\..\icub-firmware-shared\can\canProtocolLib;..\..\..\..\embot\app\skeleton;..\..\..\..\embot\prot\can;..\..\bsp;..\src + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + .\strain2c-application-v6.sct + + + --diag_suppress=L6329 + + + + + + + + main + + + main-strain2-application.cpp + 8 + ../src/main-strain2-application.cpp + + + embot_app_skeleton_os_basic.cpp + 8 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_basic.cpp + + + embot_app_skeleton_os_evthreadcan.cpp + 8 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_evthreadcan.cpp + + + adc2ft.cpp + 8 + ..\src\adc2ft.cpp + + + adc2ft.h + 5 + ..\src\adc2ft.h + + + adc2ft_data.cpp + 8 + ..\src\adc2ft_data.cpp + + + rtwtypes.h + 5 + ..\src\rtwtypes.h + + + + + stm32hal + + + stm32hal.strain2c.v1B0.lib + 4 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + + + + + stm32hal-config + + + stm32hal.startup.strain2.v190.s + 2 + ..\cfg\stm32hal.startup.strain2.v190.s + + + + + rtos + + + osal.cm4.dbg.lib + 4 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + + + eventviewer.c + 1 + ..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\src\eventviewer.c + + + cmsisos2.lib + 4 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + + + + + embot + + + embot_core.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + + + embot_core_binary.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + + + embot_os.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + + + embot_os_Thread.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + + + embot_os_theCallbackManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + + + embot_app_theJumper.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + + + embot_os_theScheduler.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + + + embot_os_theTimerManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + + + embot_os_Timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + + + embot_tools.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\tools\embot_tools.cpp + + + embot_dsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\dsp\embot_dsp.cpp + + + embot_app_theLEDmanager.cpp + 8 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + + + embot_os_Action.cpp + 8 + ..\..\..\..\embot\os\embot_os_Action.cpp + + + embot_os_rtos.cpp + 8 + ..\..\..\..\embot\os\embot_os_rtos.cpp + + + + + embot-protocol + + + embot_prot_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + + + embot_prot_can_skin_periodic.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_skin_periodic.cpp + + + embot_prot_can_inertial_periodic.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_inertial_periodic.cpp + + + embot_prot_can_motor_polling.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_motor_polling.cpp + + + embot_prot_can_motor_periodic.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_motor_periodic.cpp + + + embot_prot_can_bootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + + + embot_prot_can_analog_polling.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_analog_polling.cpp + + + embot_prot_can_analog_periodic.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_analog_periodic.cpp + + + + + embot-parser + + + embot_app_application_theCANparserBasic.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserBasic.cpp + + + embot_app_application_theCANparserSTRAIN.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserSTRAIN.cpp + + + embot_app_application_theCANparserIMU.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANparserIMU.cpp + + + embot_app_application_theCANparserTHERMO.cpp + 8 + ..\..\..\..\embot\app\embot_app_application_theCANparserTHERMO.cpp + + + + + embot-application + + + embot_app_theApplication.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theApplication.cpp + + + embot_app_theCANboardInfo.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + + + embot_app_application_theCANtracer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theCANtracer.cpp + + + embot_app_application_theIMU.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theIMU.cpp + + + embot_app_application_theSTRAIN.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_application_theSTRAIN.cpp + + + embot_app_application_theTHERMO.cpp + 8 + ..\..\..\..\embot\app\embot_app_application_theTHERMO.cpp + + + embot_app_theStorage.cpp + 8 + ..\..\..\..\embot\app\embot_app_theStorage.cpp + + + + + embot-hw + + + embot_hw.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + + + embot_hw_sys.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + + + embot_hw_bsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + + + embot_hw_FlashStorage.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + + + embot_hw_FlashBurner.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + + + embot_hw_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + + + embot_hw_flash.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + + + embot_hw_pga308.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_pga308.cpp + + + embot_hw_adc.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_adc.cpp + + + embot_hw_onewire.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_onewire.cpp + + + embot_hw_timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_timer.cpp + + + embot_hw_gpio.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_gpio.cpp + + + embot_hw_led.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + + + embot_hw_button.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_button.cpp + + + embot_hw_si7051.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_si7051.cpp + + + embot_hw_i2c.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_i2c.cpp + + + embot_hw_bno055.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_bno055.cpp + + + + + embot-hw-lowlevel + + + embot_hw_lowlevel.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + + + 2 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 1 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + + + embot::hw::bsp + + + embot_hw_bsp_strain2c.cpp + 8 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + + + + + + + + + + + + + + + + + strain2c-application-v6 + 1 + + + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.cpp b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.cpp new file mode 100644 index 0000000000..3eae6b49ff --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.cpp @@ -0,0 +1,184 @@ +// +// Non-Degree Granting Education License -- for use at non-degree +// granting, nonprofit, educational organizations only. Not for +// government, commercial, or other organizational use. +// +// File: adc2ft.cpp +// +// Code generated for Simulink model 'adc2ft'. +// +// Model version : 2.41 +// Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 +// C/C++ source code generated on : Tue Apr 13 09:39:18 2021 +// +// Target selection: ert.tlc +// Embedded hardware selection: ARM Compatible->ARM Cortex-M +// Code generation objectives: +// 1. Execution efficiency +// 2. RAM efficiency +// Validation result: Not run +// +#include "adc2ft.h" +#ifndef UCHAR_MAX +#include +#endif + +#if ( UCHAR_MAX != (0xFFU) ) || ( SCHAR_MAX != (0x7F) ) +#error Code was generated for compiler with different sized uchar/char. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( USHRT_MAX != (0xFFFFU) ) || ( SHRT_MAX != (0x7FFF) ) +#error Code was generated for compiler with different sized ushort/short. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( UINT_MAX != (0xFFFFFFFFU) ) || ( INT_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized uint/int. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +#if ( ULONG_MAX != (0xFFFFFFFFU) ) || ( LONG_MAX != (0x7FFFFFFF) ) +#error Code was generated for compiler with different sized ulong/long. \ +Consider adjusting Test hardware word size settings on the \ +Hardware Implementation pane to match your compiler word sizes as \ +defined in limits.h of the compiler. Alternatively, you can \ +select the Test hardware is the same as production hardware option and \ +select the Enable portable word sizes option on the Code Generation > \ +Verification pane for ERT based targets, which will disable the \ +preprocessor word size checks. +#endif + +// Skipping ulong_long/long_long check: insufficient preprocessor integer range. +namespace adc2ft_ns +{ + // Model step function + void adc2ft_class::step() + { + int32_T i; + int32_T i_0; + real32_T tmp[36]; + real32_T tmp_0[6]; + real32_T tmp_1[6]; + real32_T tmp_2; + for (i = 0; i < 36; i++) { + // Product: '/Divide1' incorporates: + // Constant: '/Constant' + // Constant: '/Constant2' + + rtDW.Divide1[i] = static_cast(rtP.calibration_matrix[i]) / + 32768.0F; + } + + for (i = 0; i < 6; i++) { + // DataTypeConversion: '/Data Type Conversion' incorporates: + // Inport: '/adc' + + rtDW.DataTypeConversion[i] = static_cast(rtU.adc[i]); + + // DataTypeConversion: '/Data Type Conversion2' incorporates: + // Constant: '/Constant1' + + rtDW.DataTypeConversion2[i] = static_cast + (rtP.calibration_offsets[i]); + + // Sum: '/Sum' incorporates: + // Constant: '/Constant' + // DataTypeConversion: '/Data Type Conversion' + // DataTypeConversion: '/Data Type Conversion2' + + rtDW.Sum[i] = (rtDW.DataTypeConversion[i] - 32768.0F) + + rtDW.DataTypeConversion2[i]; + + // Product: '/Divide' incorporates: + // Constant: '/Constant' + // Sum: '/Sum' + + rtDW.Divide[i] = 3.05175781E-5F * rtDW.Sum[i]; + } + + // Product: '/Product' incorporates: + // Product: '/Divide' + // Product: '/Divide1' + + for (i_0 = 0; i_0 < 36; i_0++) { + tmp[i_0] = rtDW.Divide1[i_0]; + } + + for (i = 0; i < 6; i++) { + tmp_0[i] = rtDW.Divide[i]; + tmp_1[i] = 0.0F; + } + + for (i = 0; i < 6; i++) { + for (i_0 = 0; i_0 < 6; i_0++) { + tmp_2 = tmp_1[i]; + tmp_2 += tmp[6 * i + i_0] * tmp_0[i_0]; + tmp_1[i] = tmp_2; + } + + // Product: '/Product' + rtDW.Product[i] = tmp_1[i]; + + // Outport: '/ft_q15' incorporates: + // DataTypeConversion: '/Data Type Conversion1' + // Product: '/Product' + + rtY.ft_q15[i] = static_cast(std::floor(rtDW.Product[i] * 32768.0F)); + } + + // End of Product: '/Product' + } + + // Model initialize function + void adc2ft_class::initialize() + { + // (no initialization code required) + } + + // Constructor + adc2ft_class::adc2ft_class() : + rtU(), + rtY(), + rtDW(), + rtM() + { + // Currently there is no constructor body generated. + } + + // Destructor + adc2ft_class::~adc2ft_class() + { + // Currently there is no destructor body generated. + } + + // Real-Time Model get method + adc2ft_ns::adc2ft_class::RT_MODEL * adc2ft_class::getRTM() + { + return (&rtM); + } +} + +// +// File trailer for generated code. +// +// [EOF] +// diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.h b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.h new file mode 100644 index 0000000000..b8a647b6b5 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft.h @@ -0,0 +1,136 @@ +// +// Non-Degree Granting Education License -- for use at non-degree +// granting, nonprofit, educational organizations only. Not for +// government, commercial, or other organizational use. +// +// File: adc2ft.h +// +// Code generated for Simulink model 'adc2ft'. +// +// Model version : 2.41 +// Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 +// C/C++ source code generated on : Tue Apr 13 09:39:18 2021 +// +// Target selection: ert.tlc +// Embedded hardware selection: ARM Compatible->ARM Cortex-M +// Code generation objectives: +// 1. Execution efficiency +// 2. RAM efficiency +// Validation result: Not run +// +#ifndef RTW_HEADER_adc2ft_h_ +#define RTW_HEADER_adc2ft_h_ +#include +#include "rtwtypes.h" +#include "rtw_continuous.h" +#include "rtw_solver.h" + +// Model Code Variants + +// Macros for accessing real-time model data structure +#ifndef rtmGetErrorStatus +#define rtmGetErrorStatus(rtm) ((rtm)->errorStatus) +#endif + +#ifndef rtmSetErrorStatus +#define rtmSetErrorStatus(rtm, val) ((rtm)->errorStatus = (val)) +#endif + +// Class declaration for model adc2ft +namespace adc2ft_ns +{ + class adc2ft_class { + // public data and function members + public: + // Block signals and states (default storage) for system '' + struct DW { + real32_T Divide1[36]; // '/Divide1' + real32_T DataTypeConversion[6]; // '/Data Type Conversion' + real32_T DataTypeConversion2[6]; // '/Data Type Conversion2' + real32_T Sum[6]; // '/Sum' + real32_T Divide[6]; // '/Divide' + real32_T Product[6]; // '/Product' + }; + + // External inputs (root inport signals with default storage) + struct ExtU { + uint16_T adc[6]; // '/adc' + }; + + // External outputs (root outports fed by signals with default storage) + struct ExtY { + int16_T ft_q15[6]; // '/ft_q15' + }; + + // Parameters (default storage) + struct P { + int16_T calibration_matrix[36]; // Variable: A + // Referenced by: '/Constant2' + + int16_T calibration_offsets[6]; // Variable: offsets + // Referenced by: '/Constant1' + + }; + + // Real-time Model Data Structure + struct RT_MODEL { + const char_T * volatile errorStatus; + }; + + // Tunable parameters + static P rtP; + + // External inputs + ExtU rtU; + + // External outputs + ExtY rtY; + + // model initialize function + void initialize(); + + // model step function + void step(); + + // Constructor + adc2ft_class(); + + // Destructor + ~adc2ft_class(); + + // Real-Time Model get method + adc2ft_ns::adc2ft_class::RT_MODEL * getRTM(); + + // private data and function members + private: + // Block signals and states + DW rtDW; + + // Real-Time Model + RT_MODEL rtM; + }; +} + +//- +// The generated code includes comments that allow you to trace directly +// back to the appropriate location in the model. The basic format +// is /block_name, where system is the system number (uniquely +// assigned by Simulink) and block_name is the name of the block. +// +// Use the MATLAB hilite_system command to trace the generated code back +// to the model. For example, +// +// hilite_system('') - opens system 3 +// hilite_system('/Kp') - opens and selects block Kp which resides in S3 +// +// Here is the system hierarchy for this model +// +// '' : 'adc2ft' + +#endif // RTW_HEADER_adc2ft_h_ + +// +// File trailer for generated code. +// +// [EOF] +// diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft_data.cpp b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft_data.cpp new file mode 100644 index 0000000000..9f7299e8fd --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/adc2ft_data.cpp @@ -0,0 +1,41 @@ +// +// Non-Degree Granting Education License -- for use at non-degree +// granting, nonprofit, educational organizations only. Not for +// government, commercial, or other organizational use. +// +// File: adc2ft_data.cpp +// +// Code generated for Simulink model 'adc2ft'. +// +// Model version : 2.41 +// Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 +// C/C++ source code generated on : Tue Apr 13 09:39:18 2021 +// +// Target selection: ert.tlc +// Embedded hardware selection: ARM Compatible->ARM Cortex-M +// Code generation objectives: +// 1. Execution efficiency +// 2. RAM efficiency +// Validation result: Not run +// +#include "adc2ft.h" + +// Block parameters (default storage) +adc2ft_ns::adc2ft_class::P adc2ft_ns::adc2ft_class::rtP = { + // Variable: A + // Referenced by: '/Constant2' + + { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }, + + // Variable: offsets + // Referenced by: '/Constant1' + + { 0, 0, 0, 0, 0, 0 } +}; + +// +// File trailer for generated code. +// +// [EOF] +// diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.c b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.c new file mode 100644 index 0000000000..ce006b5cbe --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.c @@ -0,0 +1,17597 @@ +/* +* +**************************************************************************** +* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH +* +* File : bno055.c +* +* Date : 2016/03/14 +* +* Revision : 2.0.3 $ +* +* Usage: Sensor Driver file for BNO055 sensor +* +**************************************************************************** +* \section License +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* Neither the name of the copyright holder nor the names of the +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND +* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR +* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER +* OR CONTRIBUTORS BE LIABLE FOR ANY +* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, +* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, +* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE +* +* The information provided is believed to be accurate and reliable. +* The copyright holder assumes no responsibility +* for the consequences of use +* of such information nor for any infringement of patents or +* other rights of third parties which may result from its use. +* No license is granted by implication or otherwise under any patent or +* patent rights of the copyright holder. +**************************************************************************/ + +/*********************************************************/ +/* INCLUDES */ +/*******************************************************/ +#include "bno055.h" +/*! file + brief */ +/* STRUCTURE DEFINITIONS */ +static struct bno055_t *p_bno055; +/* LOCAL FUNCTIONS */ +/*! + * @brief + * This API is used for initialize + * bus read, bus write function pointers,device + * address,accel revision id, gyro revision id + * mag revision id, software revision id, boot loader + * revision id and page id + * + * @param bno055 - structure pointer + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While changing the parameter of the bno055_t + * consider the following point: + * Changing the reference value of the parameter + * will changes the local copy or local reference + * make sure your changes will not + * affect the reference value of the parameter + * (Better case don't change the reference value of the parameter) + */ +BNO055_RETURN_FUNCTION_TYPE bno055_init(struct bno055_t *bno055) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + u8 bno055_page_zero_u8 = BNO055_PAGE_ZERO; + /* Array holding the Software revision id + */ + u8 a_SW_ID_u8[BNO055_REV_ID_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* stuct parameters are assign to bno055*/ + p_bno055 = bno055; + /* Write the default page as zero*/ + com_rslt = p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_PAGE_ID_REG, &bno055_page_zero_u8, BNO055_GEN_READ_WRITE_LENGTH); + /* Read the chip id of the sensor from page + zero 0x00 register*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_CHIP_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->chip_id = data_u8; + /* Read the accel revision id from page + zero 0x01 register*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_REV_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->accel_rev_id = data_u8; + /* Read the mag revision id from page + zero 0x02 register*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_REV_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->mag_rev_id = data_u8; + /* Read the gyro revision id from page + zero 0x02 register*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_REV_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->gyro_rev_id = data_u8; + /* Read the boot loader revision from page + zero 0x06 register*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_BL_REV_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->bl_rev_id = data_u8; + /* Read the software revision id from page + zero 0x04 and 0x05 register( 2 bytes of data)*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC(p_bno055->dev_addr, + BNO055_SW_REV_ID_LSB_REG, + a_SW_ID_u8, BNO055_LSB_MSB_READ_LENGTH); + a_SW_ID_u8[BNO055_SW_ID_LSB] = BNO055_GET_BITSLICE( + a_SW_ID_u8[BNO055_SW_ID_LSB], + BNO055_SW_REV_ID_LSB); + p_bno055->sw_rev_id = (u16) + ((((u32)((u8)a_SW_ID_u8[BNO055_SW_ID_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | (a_SW_ID_u8[BNO055_SW_ID_LSB])); + /* Read the page id from the register 0x07*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_PAGE_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + p_bno055->page_id = data_u8; + + return com_rslt; +} +/*! + * @brief + * This API gives data to the given register and + * the data is written in the corresponding register address + * + * @param addr_u8 : Address of the register + * @param data_u8 : Data to be written to the register + * @param len_u8 : Length of the Data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * +*/ +BNO055_RETURN_FUNCTION_TYPE bno055_write_register(u8 addr_u8, +u8 *data_u8, u8 len_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* Write the values of respective given register */ + com_rslt = p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, addr_u8, data_u8, len_u8); + } + return com_rslt; +} +/*! + * @brief This API reads the data from + * the given register address + * + * @param addr_u8 : Address of the register + * @param data_u8 : address of the variable, + * read value will be kept + * @param len_u8 : Length of the data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_register(u8 addr_u8, +u8 *data_u8, u8 len_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* Read the value from given register*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, addr_u8, data_u8, len_u8); + } + return com_rslt; +} +/*! + * @brief This API reads chip id + * from register 0x00 it is a byte of data + * + * + * @param chip_id_u8 : The chip id value 0xA0 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_chip_id(u8 *chip_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the chip id*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_CHIP_ID_REG, &data_u8, + BNO055_GEN_READ_WRITE_LENGTH); + *chip_id_u8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads software revision id + * from register 0x04 and 0x05 it is a two byte of data + * + * @param sw_id_u8 : The SW revision id + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_sw_rev_id(u16 *sw_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* array having the software revision id + data_u8[0] - LSB + data_u8[1] - MSB*/ + u8 data_u8[BNO055_REV_ID_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty*/ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value of software + revision id*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SW_REV_ID_LSB_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SW_ID_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SW_ID_LSB], + BNO055_SW_REV_ID_LSB); + *sw_id_u8 = (u16) + ((((u32)((u8)data_u8[BNO055_SW_ID_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SW_ID_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads page id + * from register 0x07 it is a byte of data + * + * + * @param page_id_u8 : The value of page id + * + * BNO055_PAGE_ZERO -> 0x00 + * BNO055_PAGE_ONE -> 0x01 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_page_id(u8 *page_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* Read the page id form 0x07*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_PAGE_ID_REG, &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8 = BNO055_GET_BITSLICE(data_u8, + BNO055_PAGE_ID); + *page_id_u8 = data_u8; + p_bno055->page_id = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write + * the page id register 0x07 + * + * @param page_id_u8 : The value of page id + * + * BNO055_PAGE_ZERO -> 0x00 + * BNO055_PAGE_ONE -> 0x01 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_page_id(u8 page_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* Read the current page*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_PAGE_ID_REG, &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + /* Check condition for communication BNO055_SUCCESS*/ + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE(data_u8r, + BNO055_PAGE_ID, page_id_u8); + /* Write the page id*/ + com_rslt += p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_PAGE_ID_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) + p_bno055->page_id = page_id_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads accel revision id + * from register 0x01 it is a byte of value + * + * @param accel_rev_id_u8 : The accel revision id 0xFB + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_rev_id( +u8 *accel_rev_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel revision id */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_REV_ID_REG, + &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + *accel_rev_id_u8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads mag revision id + * from register 0x02 it is a byte of value + * + * @param mag_rev_id_u8 : The mag revision id 0x32 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_rev_id( +u8 *mag_rev_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the mag revision id */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_REV_ID_REG, + &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + *mag_rev_id_u8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro revision id + * from register 0x03 it is a byte of value + * + * @param gyro_rev_id_u8 : The gyro revision id 0xF0 + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_rev_id( +u8 *gyro_rev_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro revision id */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_REV_ID_REG, + &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_rev_id_u8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read boot loader revision id + * from register 0x06 it is a byte of value + * + * @param bl_rev_id_u8 : The boot loader revision id + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_bl_rev_id( +u8 *bl_rev_id_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the boot loader revision id */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_BL_REV_ID_REG, + &data_u8, BNO055_GEN_READ_WRITE_LENGTH); + *bl_rev_id_u8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads acceleration data X values + * from register 0x08 and 0x09 it is a two byte data + * + * + * + * + * @param accel_x_s16 : The X raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_x(s16 *accel_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the accel x value + data_u8[BNO055_SENSOR_DATA_LSB] - x-LSB + data_u8[BNO055_SENSOR_DATA_MSB] - x-MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel x axis two byte value*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_ACCEL_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_ACCEL_DATA_X_MSB_VALUEX); + *accel_x_s16 = (s16)((((s32) + (s8)(data_u8[BNO055_SENSOR_DATA_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads acceleration data Y values + * from register 0x0A and 0x0B it is a two byte data + * + * + * + * + * @param accel_y_s16 : The Y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_y(s16 *accel_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the accel y value + data_u8[BNO055_SENSOR_DATA_LSB] - y-LSB + data_u8[BNO055_SENSOR_DATA_MSB] - y-MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel y axis two byte value*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_ACCEL_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_ACCEL_DATA_Y_MSB_VALUEY); + *accel_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads acceleration data z values + * from register 0x0C and 0x0D it is a two byte data + * + * + * + * + * @param accel_z_s16 : The z raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_z(s16 *accel_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the accel z value + data_u8[BNO055_SENSOR_DATA_LSB] - z-LSB + data_u8[BNO055_SENSOR_DATA_MSB] - z-MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel z axis two byte value*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_ACCEL_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_ACCEL_DATA_Z_MSB_VALUEZ); + *accel_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads acceleration data xyz values + * from register 0x08 to 0x0D it is a six byte data + * + * + * @param accel : The value of accel xyz data + * + * Parameter | result + * --------- | ----------------- + * x | The accel x data + * y | The accel y data + * z | The accel z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_xyz( +struct bno055_accel_t *accel) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the accel xyz value + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_ACCEL_XYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_ACCEL_XYZ_DATA_SIZE); + /* Data X*/ + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB], + BNO055_ACCEL_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB], + BNO055_ACCEL_DATA_X_MSB_VALUEX); + accel->x = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB])); + /* Data Y*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB], + BNO055_ACCEL_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB], + BNO055_ACCEL_DATA_Y_MSB_VALUEY); + accel->y = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB])); + /* Data Z*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB], + BNO055_ACCEL_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB], + BNO055_ACCEL_DATA_Z_MSB_VALUEZ); + accel->z = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads mag data x values + * from register 0x0E and 0x0F it is a two byte data + * + * + * + * + * @param mag_x_s16 : The x raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_x(s16 *mag_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the mag x value + data_u8[BNO055_SENSOR_DATA_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - x->MSB + */ + u8 data_u8[BNO055_MAG_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /*Read the mag x two bytes of data */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_MAG_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_MAG_DATA_X_MSB_VALUEX); + *mag_x_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | ( + data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads mag data y values + * from register 0x10 and 0x11 it is a two byte data + * + * + * + * + * @param mag_y_s16 : The y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_y(s16 *mag_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the mag y value + data_u8[BNO055_SENSOR_DATA_LSB] - y->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - y->MSB + */ + u8 data_u8[BNO055_MAG_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /*Read the mag y two bytes of data */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_MAG_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_MAG_DATA_Y_MSB_VALUEY); + *mag_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads mag data z values + * from register 0x12 and 0x13 it is a two byte data + * + * + * + * + * @param mag_z_s16 : The z raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_z(s16 *mag_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the mag z value + data_u8[BNO055_SENSOR_DATA_LSB] - z->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - z->MSB + */ + u8 data_u8[BNO055_MAG_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + /*Read the mag z two bytes of data */ + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_MAG_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_MAG_DATA_Z_MSB_VALUEZ); + *mag_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads mag data xyz values + * from register 0x0E to 0x13 it is a six byte data + * + * + * @param mag : The mag xyz values + * + * Parameter | result + * --------- | ----------------- + * x | The mag x data + * y | The mag y data + * z | The mag z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_xyz(struct bno055_mag_t *mag) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the mag xyz value + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_MAG_XYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /*Read the six byte value of mag xyz*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_MAG_XYZ_DATA_SIZE); + /* Data X*/ + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB], + BNO055_MAG_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB], + BNO055_MAG_DATA_X_MSB_VALUEX); + mag->x = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB])); + /* Data Y*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB], + BNO055_MAG_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB], + BNO055_MAG_DATA_Y_MSB_VALUEY); + mag->y = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB])); + /* Data Z*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB], + BNO055_MAG_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB], + BNO055_MAG_DATA_Z_MSB_VALUEZ); + mag->z = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro data x values + * from register 0x14 and 0x15 it is a two byte data + * + * + * + * + * @param gyro_x_s16 : The x raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_x(s16 *gyro_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8[BNO055_GYRO_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro 16 bit x value*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GYRO_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GYRO_DATA_X_MSB_VALUEX); + *gyro_x_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro data y values + * from register 0x16 and 0x17 it is a two byte data + * + * + * + * + * @param gyro_y_s16 : The y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_y(s16 *gyro_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8[BNO055_GYRO_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of gyro y */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GYRO_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GYRO_DATA_Y_MSB_VALUEY); + *gyro_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro data z values + * from register 0x18 and 0x19 it is a two byte data + * + * @param gyro_z_s16 : The z raw data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_z(s16 *gyro_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8[BNO055_GYRO_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro z 16 bit value*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GYRO_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GYRO_DATA_Z_MSB_VALUEZ); + *gyro_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro data xyz values + * from register 0x14 to 0x19 it is a six byte data + * + * + * @param gyro : The value of gyro xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The gyro x data + * y | The gyro y data + * z | The gyro z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_xyz(struct bno055_gyro_t *gyro) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gyro xyz value + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_GYRO_XYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the six bytes data of gyro xyz*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_GYRO_XYZ_DATA_SIZE); + /* Data x*/ + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB], + BNO055_GYRO_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB], + BNO055_GYRO_DATA_X_MSB_VALUEX); + gyro->x = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB])); + /* Data y*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB], + BNO055_GYRO_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB], + BNO055_GYRO_DATA_Y_MSB_VALUEY); + gyro->y = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB])); + /* Data z*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB], + BNO055_GYRO_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB], + BNO055_GYRO_DATA_Z_MSB_VALUEZ); + gyro->z = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gyro data z values + * from register 0x1A and 0x1B it is a two byte data + * + * @param euler_h_s16 : The raw h data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_h(s16 *euler_h_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the Euler h value + data_u8[BNO055_SENSOR_DATA_EULER_LSB] - h->LSB + data_u8[BNO055_SENSOR_DATA_EULER_MSB] - h->MSB + */ + u8 data_u8[BNO055_EULER_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the eulre heading data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_H_LSB_VALUEH_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_EULER_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_LSB], + BNO055_EULER_H_LSB_VALUEH); + data_u8[BNO055_SENSOR_DATA_EULER_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_MSB], + BNO055_EULER_H_MSB_VALUEH); + *euler_h_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_EULER_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Euler data r values + * from register 0x1C and 0x1D it is a two byte data + * + * @param euler_r_s16 : The raw r data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_r(s16 *euler_r_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the Euler r value + data_u8[BNO055_SENSOR_DATA_EULER_LSB] - r->LSB + data_u8[BNO055_SENSOR_DATA_EULER_MSB] - r->MSB + */ + u8 data_u8[BNO055_EULER_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the Euler roll data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_R_LSB_VALUER_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_EULER_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_LSB], + BNO055_EULER_R_LSB_VALUER); + data_u8[BNO055_SENSOR_DATA_EULER_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_MSB], + BNO055_EULER_R_MSB_VALUER); + *euler_r_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_EULER_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Euler data p values + * from register 0x1E and 0x1F it is a two byte data + * + * @param euler_p_s16 : The raw p data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_p(s16 *euler_p_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the Euler p value + data_u8[BNO055_SENSOR_DATA_EULER_LSB] - p->LSB + data_u8[BNO055_SENSOR_DATA_EULER_MSB] - p->MSB + */ + u8 data_u8[BNO055_EULER_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the Euler p data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_P_LSB_VALUEP_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_EULER_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_LSB], + BNO055_EULER_P_LSB_VALUEP); + data_u8[BNO055_SENSOR_DATA_EULER_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_MSB], + BNO055_EULER_P_MSB_VALUEP); + *euler_p_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_EULER_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Euler data hrp values + * from register 0x1A to 0x1F it is a six byte data + * + * + * @param euler : The Euler hrp data's + * + * Parameter | result + * --------- | ----------------- + * h | The Euler h data + * r | The Euler r data + * p | The Euler p data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_hrp( +struct bno055_euler_t *euler) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the Euler hrp value + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_LSB] - h->LSB + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_MSB] - h->MSB + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_LSB] - r->MSB + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_MSB] - r->MSB + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_LSB] - p->MSB + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_MSB] - p->MSB + */ + u8 data_u8[BNO055_EULER_HRP_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the six byte of Euler hrp data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_H_LSB_VALUEH_REG, + data_u8, BNO055_EULER_HRP_DATA_SIZE); + /* Data h*/ + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_LSB], + BNO055_EULER_H_LSB_VALUEH); + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_MSB], + BNO055_EULER_H_MSB_VALUEH); + euler->h = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_EULER_HRP_H_LSB])); + /* Data r*/ + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_LSB], + BNO055_EULER_R_LSB_VALUER); + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_MSB], + BNO055_EULER_R_MSB_VALUER); + euler->r = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_EULER_HRP_R_LSB])); + /* Data p*/ + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_LSB], + BNO055_EULER_P_LSB_VALUEP); + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_MSB], + BNO055_EULER_P_MSB_VALUEP); + euler->p = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_EULER_HRP_P_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads quaternion data w values + * from register 0x20 and 0x21 it is a two byte data + * + * @param quaternion_w_s16 : The raw w data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_w( +s16 *quaternion_w_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the Quaternion w value + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] - w->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] - w->MSB + */ + u8 data_u8[BNO055_QUATERNION_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of quaternion w data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_QUATERNION_DATA_W_LSB_VALUEW_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB], + BNO055_QUATERNION_DATA_W_LSB_VALUEW); + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB], + BNO055_QUATERNION_DATA_W_MSB_VALUEW); + *quaternion_w_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads quaternion data x values + * from register 0x22 and 0x23 it is a two byte data + * + * @param quaternion_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_x( +s16 *quaternion_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the quaternion x value + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] - x->MSB + */ + u8 data_u8[BNO055_QUATERNION_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of quaternion x data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_QUATERNION_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB], + BNO055_QUATERNION_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB], + BNO055_QUATERNION_DATA_X_MSB_VALUEX); + *quaternion_x_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads quaternion data y values + * from register 0x24 and 0x25 it is a two byte data + * + * @param quaternion_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_y( +s16 *quaternion_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the quaternion y value + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] - y->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] - y->MSB + */ + u8 data_u8[BNO055_QUATERNION_DATA_SIZE] = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of quaternion y data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_QUATERNION_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB], + BNO055_QUATERNION_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] = + BNO055_GET_BITSLICE + (data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB], + BNO055_QUATERNION_DATA_Y_MSB_VALUEY); + *quaternion_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads quaternion data z values + * from register 0x26 and 0x27 it is a two byte data + * + * @param quaternion_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_z( +s16 *quaternion_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the quaternion z value + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] - z->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] - z->MSB + */ + u8 data_u8[BNO055_QUATERNION_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of quaternion z data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_QUATERNION_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB], + BNO055_QUATERNION_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB], + BNO055_QUATERNION_DATA_Z_MSB_VALUEZ); + *quaternion_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_QUATERNION_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_QUATERNION_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Quaternion data wxyz values + * from register 0x20 to 0x27 it is a six byte data + * + * + * @param quaternion : The value of quaternion wxyz data's + * + * Parameter | result + * --------- | ----------------- + * w | The quaternion w data + * x | The quaternion x data + * y | The quaternion y data + * z | The quaternion z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_wxyz( +struct bno055_quaternion_t *quaternion) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the quaternion wxyz value + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_LSB] - w->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_MSB] - w->MSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_QUATERNION_WXYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the eight byte value + of quaternion wxyz data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_QUATERNION_DATA_W_LSB_VALUEW_REG, + data_u8, BNO055_QUATERNION_WXYZ_DATA_SIZE); + /* Data W*/ + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_LSB], + BNO055_QUATERNION_DATA_W_LSB_VALUEW); + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_MSB], + BNO055_QUATERNION_DATA_W_MSB_VALUEW); + quaternion->w = (s16)((((s32)((s8) + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_W_LSB])); + /* Data X*/ + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_LSB], + BNO055_QUATERNION_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_MSB], + BNO055_QUATERNION_DATA_X_MSB_VALUEX); + quaternion->x = (s16)((((s32)((s8) + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_X_LSB])); + /* Data Y*/ + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_LSB], + BNO055_QUATERNION_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_MSB], + BNO055_QUATERNION_DATA_Y_MSB_VALUEY); + quaternion->y = (s16)((((s32)((s8) + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Y_LSB])); + /* Data Z*/ + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_LSB], + BNO055_QUATERNION_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_MSB], + BNO055_QUATERNION_DATA_Z_MSB_VALUEZ); + quaternion->z = (s16)((((s32)((s8) + data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_QUATERNION_WXYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Linear accel data x values + * from register 0x29 and 0x2A it is a two byte data + * + * @param linear_accel_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_x( +s16 *linear_accel_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the linear accel x value + data_u8[BNO055_SENSOR_DATA_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - x->MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of linear accel x data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_LINEAR_ACCEL_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_LINEAR_ACCEL_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_LINEAR_ACCEL_DATA_X_MSB_VALUEX); + *linear_accel_x_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Linear accel data x values + * from register 0x2B and 0x2C it is a two byte data + * + * @param linear_accel_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_y( +s16 *linear_accel_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the linear accel y value + data_u8[BNO055_SENSOR_DATA_LSB] - y->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - y->MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of linear accel y data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_LINEAR_ACCEL_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_LINEAR_ACCEL_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_LINEAR_ACCEL_DATA_Y_MSB_VALUEY); + *linear_accel_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | ( + data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Linear accel data x values + * from register 0x2C and 0x2D it is a two byte data + * + * @param linear_accel_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_z( +s16 *linear_accel_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the linear accel z value + data_u8[BNO055_SENSOR_DATA_LSB] - z->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - z->MSB + */ + u8 data_u8[BNO055_ACCEL_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of linear accel z data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_LINEAR_ACCEL_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_LINEAR_ACCEL_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_LINEAR_ACCEL_DATA_Z_MSB_VALUEZ); + *linear_accel_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | ( + data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads Linear accel data xyz values + * from register 0x28 to 0x2D it is a six byte data + * + * + * @param linear_accel : The value of linear accel xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The linear accel x data + * y | The linear accel y data + * z | The linear accel z data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_xyz( +struct bno055_linear_accel_t *linear_accel) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the linear accel xyz value + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_ACCEL_XYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the six byte value + of linear accel xyz data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_LINEAR_ACCEL_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_ACCEL_XYZ_DATA_SIZE); + /* Data x*/ + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB], + BNO055_LINEAR_ACCEL_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB], + BNO055_LINEAR_ACCEL_DATA_X_MSB_VALUEX); + linear_accel->x = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB])); + /* Data y*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB], + BNO055_LINEAR_ACCEL_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB], + BNO055_LINEAR_ACCEL_DATA_Y_MSB_VALUEY); + linear_accel->y = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB])); + /* Data z*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB], + BNO055_LINEAR_ACCEL_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB], + BNO055_LINEAR_ACCEL_DATA_Z_MSB_VALUEZ); + linear_accel->z = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gravity data x values + * from register 0x2E and 0x2F it is a two byte data + * + * @param gravity_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_x( +s16 *gravity_x_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gravity x value + data_u8[BNO055_SENSOR_DATA_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - x->MSB + */ + u8 data_u8[BNO055_GRAVITY_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of gravity x data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GRAVITY_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GRAVITY_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GRAVITY_DATA_X_MSB_VALUEX); + *gravity_x_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gravity data y values + * from register 0x30 and 0x31 it is a two byte data + * + * @param gravity_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_y( +s16 *gravity_y_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gravity y value + data_u8[BNO055_SENSOR_DATA_LSB] - y->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - y->MSB + */ + u8 data_u8[BNO055_GRAVITY_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of gravity y data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GRAVITY_DATA_Y_LSB_VALUEY_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GRAVITY_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GRAVITY_DATA_Y_MSB_VALUEY); + *gravity_y_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gravity data z values + * from register 0x32 and 0x33 it is a two byte data + * + * @param gravity_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_z( +s16 *gravity_z_s16) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gravity z value + data_u8[BNO055_SENSOR_DATA_LSB] - z->LSB + data_u8[BNO055_SENSOR_DATA_MSB] - z->MSB + */ + u8 data_u8[BNO055_GRAVITY_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the two byte value + of gravity z data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GRAVITY_DATA_Z_LSB_VALUEZ_REG, + data_u8, BNO055_LSB_MSB_READ_LENGTH); + data_u8[BNO055_SENSOR_DATA_LSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_LSB], + BNO055_GRAVITY_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_MSB] = + BNO055_GET_BITSLICE(data_u8[BNO055_SENSOR_DATA_MSB], + BNO055_GRAVITY_DATA_Z_MSB_VALUEZ); + *gravity_z_s16 = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads gravity data xyz values + * from register 0x2E to 0x33 it is a six byte data + * + * + * @param gravity : The value of gravity xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The gravity x data + * y | The gravity y data + * z | The gravity z data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_xyz( +struct bno055_gravity_t *gravity) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gravity xyz value + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] - x->LSB + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] - x->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] - y->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] - z->MSB + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] - z->MSB + */ + u8 data_u8[BNO055_GRAVITY_XYZ_DATA_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the six byte value + of gravity xyz data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GRAVITY_DATA_X_LSB_VALUEX_REG, + data_u8, BNO055_GRAVITY_XYZ_DATA_SIZE); + /* Data x*/ + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB], + BNO055_GRAVITY_DATA_X_LSB_VALUEX); + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB], + BNO055_GRAVITY_DATA_X_MSB_VALUEX); + gravity->x = (s16)(((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_X_MSB]) << + BNO055_SHIFT_EIGHT_BITS) | + (data_u8[BNO055_SENSOR_DATA_XYZ_X_LSB])); + /* Data y*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB], + BNO055_GRAVITY_DATA_Y_LSB_VALUEY); + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB], + BNO055_GRAVITY_DATA_Y_MSB_VALUEY); + gravity->y = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Y_MSB])) << + BNO055_SHIFT_EIGHT_BITS) | ( + data_u8[BNO055_SENSOR_DATA_XYZ_Y_LSB])); + /* Data z*/ + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB], + BNO055_GRAVITY_DATA_Z_LSB_VALUEZ); + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB], + BNO055_GRAVITY_DATA_Z_MSB_VALUEZ); + gravity->z = (s16)((((s32) + ((s8)data_u8[BNO055_SENSOR_DATA_XYZ_Z_MSB])) << + BNO055_SHIFT_EIGHT_BITS) + | (data_u8[BNO055_SENSOR_DATA_XYZ_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API reads temperature values + * from register 0x33 it is a byte data + * + * @param temp_s8 : The raw temperature data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_temp_data(s8 *temp_s8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8 = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the raw temperature data */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_REG, &data_u8, + BNO055_GEN_READ_WRITE_LENGTH); + *temp_s8 = data_u8; + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +#ifdef BNO055_FLOAT_ENABLE +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as float + * + * @param accel_x_f : The accel x meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_x_msq( +float *accel_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw x data*/ + com_rslt += bno055_read_accel_x(®_accel_x_s16); + p_bno055->delay_msec(BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel x to m/s2*/ + data_f = + (float)(reg_accel_x_s16/BNO055_ACCEL_DIV_MSQ); + *accel_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel x raw data + * to millig output as float + * + * @param accel_x_f : The accel x millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_x_mg( +float *accel_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw x data*/ + com_rslt += bno055_read_accel_x(®_accel_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel x to m/s2*/ + data_f = + (float)(reg_accel_x_s16/BNO055_ACCEL_DIV_MG); + *accel_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as float + * + * @param accel_y_f : The accel y meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_y_msq( +float *accel_y_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_y_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + com_rslt += bno055_read_accel_y(®_accel_y_s16); + p_bno055->delay_msec(BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel y to m/s2*/ + data_f = + (float)(reg_accel_y_s16/BNO055_ACCEL_DIV_MSQ); + *accel_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel y raw data + * to millig output as float + * + * @param accel_y_f : The accel y millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_y_mg( +float *accel_y_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_y_s16 = BNO055_INIT_VALUE; + float data = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw z data*/ + com_rslt += bno055_read_accel_y(®_accel_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel z to mg*/ + data = (float)( + reg_accel_y_s16/BNO055_ACCEL_DIV_MG); + *accel_y_f = data; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel z raw data + * to meterpersecseq output as float + * + * @param accel_z_f : The accel z meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_z_msq( +float *accel_z_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw z data*/ + com_rslt += bno055_read_accel_z(®_accel_z_s16); + p_bno055->delay_msec(BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel z to m/s2*/ + data_f = + (float)(reg_accel_z_s16/BNO055_ACCEL_DIV_MSQ); + *accel_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel z raw data + * to millig output as float + * + * @param accel_z_f : The accel z millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_z_mg( +float *accel_z_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2 */ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw z data*/ + com_rslt += bno055_read_accel_z(®_accel_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw accel x to mg*/ + data_f = + (float)(reg_accel_z_s16/BNO055_ACCEL_DIV_MG); + *accel_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel xyz raw data + * to meterpersecseq output as float + * + * @param accel_xyz : The meterpersecseq data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of accel + * y | meterpersecseq data of accel + * z | meterpersecseq data of accel + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_xyz_msq( +struct bno055_accel_float_t *accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_accel_t reg_accel_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw xyz data*/ + com_rslt += bno055_read_accel_xyz(®_accel_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the accel raw xyz to meterpersecseq*/ + accel_xyz->x = + (float)(reg_accel_xyz.x/BNO055_ACCEL_DIV_MSQ); + accel_xyz->y = + (float)(reg_accel_xyz.y/BNO055_ACCEL_DIV_MSQ); + accel_xyz->z = + (float)(reg_accel_xyz.z/BNO055_ACCEL_DIV_MSQ); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel xyz raw data + * to millig output as float + * + * @param accel_xyz : The millig data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | millig data of accel + * y | millig data of accel + * z | millig data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_xyz_mg( +struct bno055_accel_float_t *accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_accel_t reg_accel_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw y data*/ + com_rslt += bno055_read_accel_xyz(®_accel_xyz); + if (com_rslt == BNO055_SUCCESS) { + /*Convert the accel raw xyz to millig */ + accel_xyz->x = + (float)(reg_accel_xyz.x/BNO055_ACCEL_DIV_MG); + accel_xyz->y = + (float)(reg_accel_xyz.y/BNO055_ACCEL_DIV_MG); + accel_xyz->z = + (float)(reg_accel_xyz.z/BNO055_ACCEL_DIV_MG); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag x raw data + * to microTesla output as float + * + * @param mag_x_f : The mag x microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_x_uT( +float *mag_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw mag x data */ + com_rslt = bno055_read_mag_x(®_mag_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw mag x to microTesla*/ + data_f = (float)(reg_mag_x_s16/BNO055_MAG_DIV_UT); + *mag_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag y raw data + * to microTesla output as float + * + * @param mag_y_f : The mag y microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_y_uT( +float *mag_y_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_y_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw mag y data */ + com_rslt = bno055_read_mag_y(®_mag_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw mag y to microTesla*/ + data_f = (float)(reg_mag_y_s16/BNO055_MAG_DIV_UT); + *mag_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag z raw data + * to microTesla output as float + * + * @param mag_z_f : The mag z microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_z_uT( +float *mag_z_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw mag z data */ + com_rslt = bno055_read_mag_z(®_mag_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw mag z to microTesla*/ + data_f = (float)(reg_mag_z_s16/BNO055_MAG_DIV_UT); + *mag_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag yz raw data + * to microTesla output as float + * + * @param mag_xyz_data : The microTesla data of mag xyz + * + * Parameter | result + * --------- | ----------------- + * x | microTesla data of mag + * y | microTesla data of mag + * z | microTesla data of mag + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_xyz_uT( +struct bno055_mag_float_t *mag_xyz_data) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_mag_t mag_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read raw mag x data */ + com_rslt = bno055_read_mag_xyz(&mag_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert mag raw xyz to microTesla*/ + mag_xyz_data->x = (float)(mag_xyz.x/BNO055_MAG_DIV_UT); + mag_xyz_data->y = (float)(mag_xyz.y/BNO055_MAG_DIV_UT); + mag_xyz_data->z = (float)(mag_xyz.z/BNO055_MAG_DIV_UT); + } else { + com_rslt = BNO055_ERROR; + } + + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro x raw data + * to dps output as float + * + * @param gyro_x_f : The gyro x dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_x_dps( +float *gyro_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_x(®_gyro_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to dps*/ + data_f = + (float)(reg_gyro_x_s16/BNO055_GYRO_DIV_DPS); + *gyro_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro x raw data + * to rps output as float + * + * @param gyro_x_f : The gyro x dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_x_rps( +float *gyro_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_x(®_gyro_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to rps*/ + data_f = + (float)(reg_gyro_x_s16/BNO055_GYRO_DIV_RPS); + *gyro_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro y raw data + * to dps output as float + * + * @param gyro_y_f : The gyro y dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_y_dps( +float *gyro_y_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_y_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw y data */ + com_rslt += bno055_read_gyro_y(®_gyro_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to dps*/ + data_f = + (float)(reg_gyro_y_s16/BNO055_GYRO_DIV_DPS); + *gyro_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro y raw data + * to rps output as float + * + * @param gyro_y_f : The gyro y dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_y_rps( +float *gyro_y_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_y_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw y data */ + com_rslt += bno055_read_gyro_y(®_gyro_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to rps*/ + data_f = + (float)(reg_gyro_y_s16/BNO055_GYRO_DIV_RPS); + *gyro_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro z raw data + * to dps output as float + * + * @param gyro_z_f : The gyro z dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_z_dps( +float *gyro_z_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw z data */ + com_rslt += bno055_read_gyro_z(®_gyro_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to dps*/ + data_f = + (float)(reg_gyro_z_s16/BNO055_GYRO_DIV_DPS); + *gyro_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro z raw data + * to rps output as float + * + * @param gyro_z_f : The gyro z rps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_z_rps( +float *gyro_z_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_z(®_gyro_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro x to rps*/ + data_f = + (float)(reg_gyro_z_s16/BNO055_GYRO_DIV_RPS); + *gyro_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro xyz raw data + * to dps output as float + * + * @param gyro_xyz_data : The dps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | dps data of gyro + * y | dps data of gyro + * z | dps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_xyz_dps( +struct bno055_gyro_float_t *gyro_xyz_data) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gyro_t gyro_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw xyz data */ + com_rslt += bno055_read_gyro_xyz(&gyro_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert gyro raw xyz to dps*/ + gyro_xyz_data->x = + (float)(gyro_xyz.x/BNO055_GYRO_DIV_DPS); + gyro_xyz_data->y = + (float)(gyro_xyz.y/BNO055_GYRO_DIV_DPS); + gyro_xyz_data->z = + (float)(gyro_xyz.z/BNO055_GYRO_DIV_DPS); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro xyz raw data + * to rps output as float + * + * @param gyro_xyz_data : The rps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | rps data of gyro + * y | rps data of gyro + * z | rps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_xyz_rps( +struct bno055_gyro_float_t *gyro_xyz_data) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gyro_t gyro_xyz = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw xyz data */ + com_rslt += bno055_read_gyro_xyz(&gyro_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert gyro raw xyz to rps*/ + gyro_xyz_data->x = + (float)(gyro_xyz.x/BNO055_GYRO_DIV_RPS); + gyro_xyz_data->y = + (float)(gyro_xyz.y/BNO055_GYRO_DIV_RPS); + gyro_xyz_data->z = + (float)(gyro_xyz.z/BNO055_GYRO_DIV_RPS); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler h raw data + * to degree output as float + * + * @param euler_h_f : The float value of Euler h degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_h_deg( +float *euler_h_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_h_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw h data*/ + com_rslt += bno055_read_euler_h(®_euler_h_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler h data to degree*/ + data_f = + (float)(reg_euler_h_s16/BNO055_EULER_DIV_DEG); + *euler_h_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler h raw data + * to radians output as float + * + * @param euler_h_f : The float value of Euler h radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_h_rad( +float *euler_h_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_h_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw h data*/ + com_rslt += bno055_read_euler_h(®_euler_h_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler h data to degree*/ + data_f = + (float)(reg_euler_h_s16/BNO055_EULER_DIV_RAD); + *euler_h_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler r raw data + * to degree output as float + * + * @param euler_r_f : The float value of Euler r degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_r_deg( +float *euler_r_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_r = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw r data*/ + com_rslt += bno055_read_euler_r(®_euler_r); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler r data to degree*/ + data_f = (float)( + reg_euler_r/BNO055_EULER_DIV_DEG); + *euler_r_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler r raw data + * to radians output as float + * + * @param euler_r_f : The float value of Euler r radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_r_rad( +float *euler_r_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_r_f = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw r data*/ + com_rslt += bno055_read_euler_r(®_euler_r_f); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler r data to radians*/ + data_f = + (float)(reg_euler_r_f/BNO055_EULER_DIV_RAD); + *euler_r_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler p raw data + * to degree output as float + * + * @param euler_p_f : The float value of Euler p degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_p_deg( +float *euler_p_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_p_f = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw p data*/ + com_rslt += bno055_read_euler_p(®_euler_p_f); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler p data to degree*/ + data_f = + (float)(reg_euler_p_f/BNO055_EULER_DIV_DEG); + *euler_p_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler p raw data + * to radians output as float + * + * @param euler_p_f : The float value of Euler p radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_p_rad( +float *euler_p_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_p_f = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw r data*/ + com_rslt += bno055_read_euler_p(®_euler_p_f); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler r data to radians*/ + data_f = + (float)(reg_euler_p_f/BNO055_EULER_DIV_RAD); + *euler_p_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler hrp raw data + * to degree output as float + * + * @param euler_hpr : The degree data of Euler hrp + * + * Parameter | result + * --------- | ----------------- + * h | degree data of Euler + * r | degree data of Euler + * p | degree data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_hpr_deg( +struct bno055_euler_float_t *euler_hpr) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_euler_t reg_euler = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw hrp data*/ + com_rslt += bno055_read_euler_hrp(®_euler); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler hrp to degree*/ + euler_hpr->h = + (float)(reg_euler.h/BNO055_EULER_DIV_DEG); + euler_hpr->p = + (float)(reg_euler.p/BNO055_EULER_DIV_DEG); + euler_hpr->r = + (float)(reg_euler.r/BNO055_EULER_DIV_DEG); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler xyz raw data + * to radians output as float + * + * @param euler_hpr : The radians data of Euler hrp + * + * Parameter | result + * --------- | ----------------- + * h | radians data of Euler + * r | radians data of Euler + * p | radians data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_hpr_rad( +struct bno055_euler_float_t *euler_hpr) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_euler_t reg_euler = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw hrp data*/ + com_rslt += bno055_read_euler_hrp(®_euler); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw hrp to radians */ + euler_hpr->h = + (float)(reg_euler.h/BNO055_EULER_DIV_RAD); + euler_hpr->p = + (float)(reg_euler.p/BNO055_EULER_DIV_RAD); + euler_hpr->r = + (float)(reg_euler.r/BNO055_EULER_DIV_RAD); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel x raw data to meterpersecseq output as float + * + * @param linear_accel_x_f : The float value of linear accel x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_x_msq( +float *linear_accel_x_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_x(®_linear_accel_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw linear accel x to m/s2*/ + data_f = + (float)(reg_linear_accel_x_s16/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel y raw data to meterpersecseq output as float + * + * @param linear_accel_y_f : The float value of linear accel y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_y_msq( +float *linear_accel_y_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_y = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read the raw y of linear accel */ + com_rslt = bno055_read_linear_accel_y(®_linear_accel_y); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw linear accel x to m/s2*/ + data_f = (float) + (reg_linear_accel_y/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel z raw data to meterpersecseq output as float + * + * @param linear_accel_z_f : The float value of linear accel z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_z_msq( +float *linear_accel_z_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_z = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_z(®_linear_accel_z); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw linear accel z to m/s2*/ + data_f = (float) + (reg_linear_accel_z/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear accel xyz raw data + * to meterpersecseq output as float + * + * @param linear_accel_xyz : The meterpersecseq data of linear accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of linear accel + * y | meterpersecseq data of linear accel + * z | meterpersecseq data of linear accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_xyz_msq( +struct bno055_linear_accel_float_t *linear_accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_linear_accel_t reg_linear_accel = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_xyz(®_linear_accel); + if (com_rslt == BNO055_SUCCESS) { + linear_accel_xyz->x = + (float)(reg_linear_accel.x/BNO055_LINEAR_ACCEL_DIV_MSQ); + linear_accel_xyz->y = + (float)(reg_linear_accel.y/BNO055_LINEAR_ACCEL_DIV_MSQ); + linear_accel_xyz->z = + (float)(reg_linear_accel.z/BNO055_LINEAR_ACCEL_DIV_MSQ); + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * x raw data to meterpersecseq output as float + * + * @param gravity_x_f : The float value of gravity x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_x_msq( +float *gravity_x_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_x_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw gravity of x*/ + com_rslt = bno055_read_gravity_x(®_gravity_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gravity x to m/s2*/ + data_f = (float)(reg_gravity_x_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_x_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * y raw data to meterpersecseq output as float + * + * @param gravity_y_f : The float value of gravity y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_y_msq( +float *gravity_y_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_y_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw gravity of y*/ + com_rslt = bno055_read_gravity_y(®_gravity_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gravity y to m/s2*/ + data_f = (float)(reg_gravity_y_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_y_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * z raw data to meterpersecseq output as float + * + * @param gravity_z_f : The float value of gravity z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_z_msq( +float *gravity_z_f) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_z_s16 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + /* Read raw gravity of z */ + com_rslt = bno055_read_gravity_z(®_gravity_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gravity z to m/s2*/ + data_f = (float)(reg_gravity_z_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_z_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity xyz raw data + * to meterpersecseq output as float + * + * @param gravity_xyz : The meterpersecseq data of gravity xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of gravity + * y | meterpersecseq data of gravity + * z | meterpersecseq data of gravity + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gravity_xyz_msq( +struct bno055_gravity_float_t *gravity_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gravity_t reg_gravity_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read raw gravity of xyz */ + com_rslt = bno055_read_gravity_xyz(®_gravity_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gravity xyz to meterpersecseq */ + gravity_xyz->x = + (float)(reg_gravity_xyz.x/BNO055_GRAVITY_DIV_MSQ); + gravity_xyz->y = + (float)(reg_gravity_xyz.y/BNO055_GRAVITY_DIV_MSQ); + gravity_xyz->z = + (float)(reg_gravity_xyz.z/BNO055_GRAVITY_DIV_MSQ); + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the temperature + * data to Fahrenheit output as float + * + * @param temp_f : The float value of temperature Fahrenheit + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_temp_fahrenheit( +float *temp_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s8 reg_temp_s8 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 temp_unit_u8 = BNO055_INIT_VALUE; + /* Read the current temperature unit and set the + unit as Fahrenheit if the unit is in Celsius */ + com_rslt = bno055_get_temp_unit(&temp_unit_u8); + if (temp_unit_u8 != BNO055_TEMP_UNIT_FAHRENHEIT) + com_rslt += bno055_set_temp_unit(BNO055_TEMP_UNIT_FAHRENHEIT); + if (com_rslt == BNO055_SUCCESS) { + /* Read the raw temperature data */ + com_rslt += bno055_read_temp_data(®_temp_s8); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw temperature data to Fahrenheit*/ + data_f = (float) + (reg_temp_s8/BNO055_TEMP_DIV_FAHRENHEIT); + *temp_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the temperature + * data to Celsius output as float + * + * @param temp_f : The float value of temperature Celsius + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_temp_celsius( +float *temp_f) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s8 reg_temp_s8 = BNO055_INIT_VALUE; + float data_f = BNO055_INIT_VALUE; + u8 temp_unit_u8 = BNO055_INIT_VALUE; + /* Read the current temperature unit and set the + unit as Fahrenheit if the unit is in Celsius */ + com_rslt = bno055_get_temp_unit(&temp_unit_u8); + if (temp_unit_u8 != BNO055_TEMP_UNIT_CELSIUS) + com_rslt += bno055_set_temp_unit(BNO055_TEMP_UNIT_CELSIUS); + if (com_rslt == BNO055_SUCCESS) { + /* Read the raw temperature data */ + com_rslt += bno055_read_temp_data(®_temp_s8); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw temperature data to Fahrenheit*/ + data_f = + (float)(reg_temp_s8/BNO055_TEMP_DIV_CELSIUS); + *temp_f = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +#endif +#ifdef BNO055_DOUBLE_ENABLE +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as double + * + * @param accel_x_d : The accel x meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_x_msq( +double *accel_x_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_x_s16 = BNO055_INIT_VALUE; + double data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw y data*/ + com_rslt += bno055_read_accel_x(®_accel_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw x to m/s2 */ + data_f = + (double)(reg_accel_x_s16/BNO055_ACCEL_DIV_MSQ); + *accel_x_d = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel x raw data + * to millig output as double + * + * @param accel_x_d : The accel x millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_x_mg( +double *accel_x_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_x_s16 = BNO055_INIT_VALUE; + double data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw y data*/ + com_rslt += bno055_read_accel_x(®_accel_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw x to mg */ + data_f = + (double)(reg_accel_x_s16/BNO055_ACCEL_DIV_MG); + *accel_x_d = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel y raw data + * to meterpersecseq output as double + * + * @param accel_y_d : The accel y meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_y_msq( +double *accel_y_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_y_s16 = BNO055_INIT_VALUE; + double data_f = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw y data*/ + com_rslt += bno055_read_accel_y(®_accel_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw x to m/s2 */ + data_f = + (double)(reg_accel_y_s16/BNO055_ACCEL_DIV_MSQ); + *accel_y_d = data_f; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel y raw data + * to millig output as double + * + * @param accel_y_d : The accel y millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_y_mg( +double *accel_y_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw y data*/ + com_rslt += bno055_read_accel_y(®_accel_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw y to mg */ + data_d = + (double)(reg_accel_y_s16/BNO055_ACCEL_DIV_MG); + *accel_y_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel z raw data + * to meterpersecseq output as double + * + * @param accel_z_d : The accel z meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_z_msq( +double *accel_z_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw z data*/ + com_rslt += bno055_read_accel_z(®_accel_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw z to m/s2 */ + data_d = + (double)(reg_accel_z_s16/BNO055_ACCEL_DIV_MSQ); + *accel_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel z raw data + * to millig output as double + * + * @param accel_z_d : The accel z millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_z_mg( +double *accel_z_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_accel_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as mg if the unit is in m/s2*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw z data*/ + com_rslt += bno055_read_accel_z(®_accel_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw z to mg */ + data_d = + (double)(reg_accel_z_s16/BNO055_ACCEL_DIV_MG); + *accel_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel xyz raw data + * to meterpersecseq output as double + * + * @param accel_xyz : The meterpersecseq data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of accel + * y | meterpersecseq data of accel + * z | meterpersecseq data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_xyz_msq( +struct bno055_accel_double_t *accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_accel_t reg_accel_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MSQ) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MSQ); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw xyz data*/ + com_rslt += bno055_read_accel_xyz(®_accel_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw xyz to m/s2*/ + accel_xyz->x = + (double)(reg_accel_xyz.x/BNO055_ACCEL_DIV_MSQ); + accel_xyz->y = + (double)(reg_accel_xyz.y/BNO055_ACCEL_DIV_MSQ); + accel_xyz->z = + (double)(reg_accel_xyz.z/BNO055_ACCEL_DIV_MSQ); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the accel xyz raw data + * to millig output as double + * + * @param accel_xyz : The millig data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | millig data of accel + * y | millig data of accel + * z | millig data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_xyz_mg( +struct bno055_accel_double_t *accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_accel_t reg_accel_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 accel_unit_u8 = BNO055_INIT_VALUE; + /* Read the current accel unit and set the + unit as m/s2 if the unit is in mg*/ + com_rslt = bno055_get_accel_unit(&accel_unit_u8); + if (accel_unit_u8 != BNO055_ACCEL_UNIT_MG) + com_rslt += bno055_set_accel_unit(BNO055_ACCEL_UNIT_MG); + if (com_rslt == BNO055_SUCCESS) { + /* Read the accel raw xyz data*/ + com_rslt += bno055_read_accel_xyz(®_accel_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw xyz to mg*/ + accel_xyz->x = + (double)(reg_accel_xyz.x/BNO055_ACCEL_DIV_MG); + accel_xyz->y = + (double)(reg_accel_xyz.y/BNO055_ACCEL_DIV_MG); + accel_xyz->z = + (double)(reg_accel_xyz.z/BNO055_ACCEL_DIV_MG); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag x raw data + * to microTesla output as double + * + * @param mag_x_d : The mag x microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_x_uT( +double *mag_x_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_x_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw mag x data */ + com_rslt = bno055_read_mag_x(®_mag_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw mag x to microTesla */ + data_d = (double)(reg_mag_x_s16/BNO055_MAG_DIV_UT); + *mag_x_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag y raw data + * to microTesla output as double + * + * @param mag_y_d : The mag y microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_y_uT( +double *mag_y_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw mag y data */ + com_rslt = bno055_read_mag_y(®_mag_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw mag y to microTesla */ + data_d = (double)(reg_mag_y_s16/BNO055_MAG_DIV_UT); + *mag_y_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag z raw data + * to microTesla output as double + * + * @param mag_z_d : The mag z microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_z_uT( +double *mag_z_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_mag_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw mag x */ + com_rslt = bno055_read_mag_z(®_mag_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw mag x to microTesla */ + data_d = (double)(reg_mag_z_s16/BNO055_MAG_DIV_UT); + *mag_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the mag yz raw data + * to microTesla output as double + * + * @param mag_xyz : The microTesla data of mag xyz + * + * Parameter | result + * --------- | ----------------- + * x | microTesla data of mag + * y | microTesla data of mag + * z | microTesla data of mag + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_xyz_uT( +struct bno055_mag_double_t *mag_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_mag_t reg_mag_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read raw mag xyz data */ + com_rslt = bno055_read_mag_xyz(®_mag_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw mag xyz to microTesla*/ + mag_xyz->x = + (double)(reg_mag_xyz.x/BNO055_MAG_DIV_UT); + mag_xyz->y = + (double)(reg_mag_xyz.y/BNO055_MAG_DIV_UT); + mag_xyz->z = + (double)(reg_mag_xyz.z/BNO055_MAG_DIV_UT); + } else { + com_rslt = BNO055_ERROR; + } + + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro x raw data + * to dps output as double + * + * @param gyro_x_d : The gyro x dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_x_dps( +double *gyro_x_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_x_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_x(®_gyro_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro x to dps */ + data_d = + (double)(reg_gyro_x_s16/BNO055_GYRO_DIV_DPS); + *gyro_x_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro x raw data + * to rps output as double + * + * @param gyro_x_d : The gyro x dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_x_rps( +double *gyro_x_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_x_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_x(®_gyro_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro x to rps */ + data_d = + (double)(reg_gyro_x_s16/BNO055_GYRO_DIV_RPS); + *gyro_x_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro y raw data + * to dps output as double + * + * @param gyro_y_d : The gyro y dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_y_dps( +double *gyro_y_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw y data */ + com_rslt += bno055_read_gyro_y(®_gyro_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro y to dps */ + data_d = + (double)(reg_gyro_y_s16/BNO055_GYRO_DIV_DPS); + *gyro_y_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro y raw data + * to rps output as double + * + * @param gyro_y_d : The gyro y dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_y_rps( +double *gyro_y_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw y data */ + com_rslt += bno055_read_gyro_y(®_gyro_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro y to rps */ + data_d = + (double)(reg_gyro_y_s16/BNO055_GYRO_DIV_RPS); + *gyro_y_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro z raw data + * to dps output as double + * + * @param gyro_z_d : The gyro z dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_z_dps( +double *gyro_z_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw z data */ + com_rslt += bno055_read_gyro_z(®_gyro_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro z to dps */ + data_d = + (double)(reg_gyro_z_s16/BNO055_GYRO_DIV_DPS); + *gyro_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro z raw data + * to rps output as double + * + * @param gyro_z_d : The gyro z rps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_z_rps( +double *gyro_z_d) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gyro_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_z(®_gyro_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gyro x to rps */ + data_d = + (double)(reg_gyro_z_s16/BNO055_GYRO_DIV_RPS); + *gyro_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro xyz raw data + * to dps output as double + * + * @param gyro_xyz : The dps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | dps data of gyro + * y | dps data of gyro + * z | dps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_xyz_dps( +struct bno055_gyro_double_t *gyro_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gyro_t reg_gyro_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as dps if the unit is in rps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_DPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_DPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw xyz data */ + com_rslt += bno055_read_gyro_xyz(®_gyro_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert gyro raw xyz to dps*/ + gyro_xyz->x = + (double)(reg_gyro_xyz.x/BNO055_GYRO_DIV_DPS); + gyro_xyz->y = + (double)(reg_gyro_xyz.y/BNO055_GYRO_DIV_DPS); + gyro_xyz->z = + (double)(reg_gyro_xyz.z/BNO055_GYRO_DIV_DPS); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gyro xyz raw data + * to rps output as double + * + * @param gyro_xyz : The rps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | rps data of gyro + * y | rps data of gyro + * z | rps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_xyz_rps( +struct bno055_gyro_double_t *gyro_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gyro_t reg_gyro_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 gyro_unit_u8 = BNO055_INIT_VALUE; + /* Read the current gyro unit and set the + unit as rps if the unit is in dps */ + com_rslt = bno055_get_gyro_unit(&gyro_unit_u8); + if (gyro_unit_u8 != BNO055_GYRO_UNIT_RPS) + com_rslt += bno055_set_gyro_unit(BNO055_GYRO_UNIT_RPS); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro raw x data */ + com_rslt += bno055_read_gyro_xyz(®_gyro_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw gyro xyz to rps*/ + gyro_xyz->x = + (double)(reg_gyro_xyz.x/BNO055_GYRO_DIV_RPS); + gyro_xyz->y = + (double)(reg_gyro_xyz.y/BNO055_GYRO_DIV_RPS); + gyro_xyz->z = + (double)(reg_gyro_xyz.z/BNO055_GYRO_DIV_RPS); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler h raw data + * to degree output as double + * + * @param euler_h_d : The double value of Euler h degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_h_deg( +double *euler_h_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_h_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw h data*/ + com_rslt += bno055_read_euler_h(®_euler_h_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler h to degree */ + data_d = + (double)(reg_euler_h_s16/BNO055_EULER_DIV_DEG); + *euler_h_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler h raw data + * to radians output as double + * + * @param euler_h_d : The double value of Euler h radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_h_rad( +double *euler_h_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_h_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw h data*/ + com_rslt += bno055_read_euler_h(®_euler_h_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler h to radians */ + data_d = + (double)(reg_euler_h_s16/BNO055_EULER_DIV_RAD); + *euler_h_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler r raw data + * to degree output as double + * + * @param euler_r_d : The double value of Euler r degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_r_deg( +double *euler_r_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_r_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw r data*/ + com_rslt += bno055_read_euler_r(®_euler_r_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler r to degree */ + data_d = + (double)(reg_euler_r_s16/BNO055_EULER_DIV_DEG); + *euler_r_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler r raw data + * to radians output as double + * + * @param euler_r_d : The double value of Euler r radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_r_rad( +double *euler_r_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_r_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw r data*/ + com_rslt += bno055_read_euler_r(®_euler_r_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler r to radians */ + data_d = + (double)(reg_euler_r_s16/BNO055_EULER_DIV_RAD); + *euler_r_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler p raw data + * to degree output as double + * + * @param euler_p_d : The double value of Euler p degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_p_deg( +double *euler_p_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_p_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw p data*/ + com_rslt += bno055_read_euler_p(®_euler_p_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler p to degree*/ + data_d = + (double)(reg_euler_p_s16/BNO055_EULER_DIV_DEG); + *euler_p_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler p raw data + * to radians output as double + * + * @param euler_p_d : The double value of Euler p radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_p_rad( +double *euler_p_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_euler_p_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw p data*/ + com_rslt += bno055_read_euler_p(®_euler_p_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw p to radians*/ + data_d = + (double)(reg_euler_p_s16/BNO055_EULER_DIV_RAD); + *euler_p_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler hpr raw data + * to degree output as double + * + * @param euler_hpr : The degree data of Euler hpr + * + * Parameter | result + * --------- | ----------------- + * h | degree data of Euler + * r | degree data of Euler + * p | degree data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_hpr_deg( +struct bno055_euler_double_t *euler_hpr) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_euler_t reg_euler = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as degree if the unit is in radians */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_DEG) + com_rslt += bno055_set_euler_unit(BNO055_EULER_UNIT_DEG); + if (com_rslt == BNO055_SUCCESS) { + /* Read Euler raw h data*/ + com_rslt += bno055_read_euler_hrp(®_euler); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler hrp to degree*/ + euler_hpr->h = + (double)(reg_euler.h/BNO055_EULER_DIV_DEG); + euler_hpr->p = + (double)(reg_euler.p/BNO055_EULER_DIV_DEG); + euler_hpr->r = + (double)(reg_euler.r/BNO055_EULER_DIV_DEG); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the Euler hpr raw data + * to radians output as double + * + * @param euler_hpr : The radians data of Euler hpr + * + * Parameter | result + * --------- | ----------------- + * h | radians data of Euler + * r | radians data of Euler + * p | radians data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_hpr_rad( +struct bno055_euler_double_t *euler_hpr) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_euler_t reg_euler = {BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + u8 euler_unit_u8 = BNO055_INIT_VALUE; + /* Read the current Euler unit and set the + unit as radians if the unit is in degree */ + com_rslt = bno055_get_euler_unit(&euler_unit_u8); + if (euler_unit_u8 != BNO055_EULER_UNIT_RAD) + com_rslt = bno055_set_euler_unit(BNO055_EULER_UNIT_RAD); + if (com_rslt == BNO055_SUCCESS) { + /* Read the raw hrp */ + com_rslt = bno055_read_euler_hrp(®_euler); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw Euler hrp to radians*/ + euler_hpr->h = + (double)(reg_euler.h/BNO055_EULER_DIV_RAD); + euler_hpr->p = + (double)(reg_euler.p/BNO055_EULER_DIV_RAD); + euler_hpr->r = + (double)(reg_euler.r/BNO055_EULER_DIV_RAD); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel x raw data to meterpersecseq output as double + * + * @param linear_accel_x_d : The double value of + * linear accel x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_x_msq( +double *linear_accel_x_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_x_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_x(®_linear_accel_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw x to m/s2 */ + data_d = (double) + (reg_linear_accel_x_s16/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_x_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel y raw data to meterpersecseq output as double + * + * @param linear_accel_y_d : The double value of + * linear accel y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_y_msq( +double *linear_accel_y_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_y(®_linear_accel_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw y to m/s2 */ + data_d = (double) + (reg_linear_accel_y_s16/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_y_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear + * accel z raw data to meterpersecseq output as double + * + * @param linear_accel_z_d : The double value of + * linear accel z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_z_msq( +double *linear_accel_z_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_linear_accel_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read the raw x of linear accel */ + com_rslt = bno055_read_linear_accel_z(®_linear_accel_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw z to m/s2 */ + data_d = + (double)(reg_linear_accel_z_s16/BNO055_LINEAR_ACCEL_DIV_MSQ); + *linear_accel_z_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the linear accel xyz raw data + * to meterpersecseq output as double + * + * @param linear_accel_xyz : The meterpersecseq data of linear accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of linear accel + * y | meterpersecseq data of linear accel + * z | meterpersecseq data of linear accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_xyz_msq( +struct bno055_linear_accel_double_t *linear_accel_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_linear_accel_t reg_linear_accel_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read the raw xyz of linear accel */ + com_rslt = bno055_read_linear_accel_xyz(®_linear_accel_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert the raw xyz of linear accel to m/s2 */ + linear_accel_xyz->x = + (double)(reg_linear_accel_xyz.x/BNO055_LINEAR_ACCEL_DIV_MSQ); + linear_accel_xyz->y = + (double)(reg_linear_accel_xyz.y/BNO055_LINEAR_ACCEL_DIV_MSQ); + linear_accel_xyz->z = + (double)(reg_linear_accel_xyz.z/BNO055_LINEAR_ACCEL_DIV_MSQ); + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * x raw data to meterpersecseq output as double + * + * @param gravity_x_d : The double value of gravity x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_x_msq( +double *gravity_x_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_x_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw gravity of x*/ + com_rslt = bno055_read_gravity_x(®_gravity_x_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gravity of x to m/s2 */ + data_d = + (double)(reg_gravity_x_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_x_d = data_d; + } else { + com_rslt = BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * y raw data to meterpersecseq output as double + * + * @param gravity_y_d : The double value of gravity y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_y_msq( +double *gravity_y_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_y_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw gravity of y */ + com_rslt = bno055_read_gravity_y(®_gravity_y_s16); + if (com_rslt == BNO055_SUCCESS) { + /* convert raw gravity of y to m/s2 */ + data_d = + (double)(reg_gravity_y_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_y_d = data_d; + } else { + com_rslt += BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity + * z raw data to meterpersecseq output as double + * + * @param gravity_z_d : The double value of gravity z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_z_msq( +double *gravity_z_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s16 reg_gravity_z_s16 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + /* Read raw gravity of z */ + com_rslt = bno055_read_gravity_z(®_gravity_z_s16); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gravity of z to m/s2 */ + data_d = + (double)(reg_gravity_z_s16/BNO055_GRAVITY_DIV_MSQ); + *gravity_z_d = data_d; + } else { + com_rslt += BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the gravity xyz raw data + * to meterpersecseq output as double + * + * @param gravity_xyz : The meterpersecseq data of gravity xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of gravity + * y | meterpersecseq data of gravity + * z | meterpersecseq data of gravity + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gravity_xyz_msq( +struct bno055_gravity_double_t *gravity_xyz) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + struct bno055_gravity_t reg_gravity_xyz = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + /* Read raw gravity of xyz */ + com_rslt = bno055_read_gravity_xyz(®_gravity_xyz); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw gravity of xyz to m/s2 */ + gravity_xyz->x = + (double)(reg_gravity_xyz.x/BNO055_GRAVITY_DIV_MSQ); + gravity_xyz->y = + (double)(reg_gravity_xyz.y/BNO055_GRAVITY_DIV_MSQ); + gravity_xyz->z = + (double)(reg_gravity_xyz.z/BNO055_GRAVITY_DIV_MSQ); + } else { + com_rslt += BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the temperature + * data to Fahrenheit output as double + * + * @param temp_d : The double value of temperature Fahrenheit + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_temp_fahrenheit( +double *temp_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s8 reg_temp_s8 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 temp_unit_u8 = BNO055_INIT_VALUE; + /* Read the current temperature unit and set the + unit as Fahrenheit if the unit is in Celsius */ + com_rslt = bno055_get_temp_unit(&temp_unit_u8); + if (temp_unit_u8 != BNO055_TEMP_UNIT_FAHRENHEIT) + com_rslt += bno055_set_temp_unit(BNO055_TEMP_UNIT_FAHRENHEIT); + if (com_rslt == BNO055_SUCCESS) { + /* Read the raw temperature data */ + com_rslt += bno055_read_temp_data(®_temp_s8); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw temperature data to Fahrenheit*/ + data_d = (double)(reg_temp_s8/ + BNO055_TEMP_DIV_FAHRENHEIT); + *temp_d = data_d; + } else { + com_rslt += BNO055_ERROR; + } + } else { + com_rslt += BNO055_ERROR; + } + return com_rslt; +} +/*! + * @brief This API is used to convert the temperature + * data to Celsius output as double + * + * @param temp_d : The double value of temperature Celsius + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_temp_celsius( +double *temp_d) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + s8 reg_temp_s8 = BNO055_INIT_VALUE; + double data_d = BNO055_INIT_VALUE; + u8 temp_unit_u8 = BNO055_INIT_VALUE; + /* Read the current temperature unit and set the + unit as Fahrenheit if the unit is in Celsius */ + com_rslt = bno055_get_temp_unit(&temp_unit_u8); + if (temp_unit_u8 != BNO055_TEMP_UNIT_CELSIUS) + com_rslt += bno055_set_temp_unit(BNO055_TEMP_UNIT_CELSIUS); + if (com_rslt == BNO055_SUCCESS) { + /* Read the raw temperature data */ + com_rslt += bno055_read_temp_data(®_temp_s8); + if (com_rslt == BNO055_SUCCESS) { + /* Convert raw temperature data to Fahrenheit*/ + data_d = + (double)(reg_temp_s8/BNO055_TEMP_DIV_CELSIUS); + *temp_d = data_d; + } else { + com_rslt += BNO055_ERROR; + } + } else { + com_rslt += BNO055_ERROR; + } + return com_rslt; +} +#endif +/*! + * @brief This API used to read + * mag calibration status from register from 0x35 bit 0 and 1 + * + * @param mag_calib_u8 : The value of mag calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_calib_stat( +u8 *mag_calib_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, mag calib + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the mag calib stat_s8 */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_CALIB_STAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *mag_calib_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_CALIB_STAT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * accel calibration status from register from 0x35 bit 2 and 3 + * + * @param accel_calib_u8 : The value of accel calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_calib_stat( +u8 *accel_calib_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty*/ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel calib + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel calib stat_s8 */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_CALIB_STAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_calib_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_CALIB_STAT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * gyro calibration status from register from 0x35 bit 4 and 5 + * + * @param gyro_calib_u8 : The value of gyro calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_calib_stat( +u8 *gyro_calib_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro calib + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro calib status */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_CALIB_STAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_calib_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_CALIB_STAT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * system calibration status from register from 0x35 bit 6 and 7 + * + * @param sys_calib_u8 : The value of system calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_calib_stat( +u8 *sys_calib_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty*/ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page,system calib + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the system calib */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_CALIB_STAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sys_calib_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_SYS_CALIB_STAT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * self test of accel from register from 0x36 bit 0 + * + * @param selftest_accel_u8 : The value of self test of accel + * + * selftest_accel_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_accel( +u8 *selftest_accel_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel self test is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel self test */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_ACCEL_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *selftest_accel_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_SELFTEST_ACCEL); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * self test of mag from register from 0x36 bit 1 + * + * @param selftest_mag_u8 : The value of self test of mag + * + * selftest_mag_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_mag( +u8 *selftest_mag_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, self test of mag is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the mag self test */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_MAG_REG, &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *selftest_mag_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_SELFTEST_MAG); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * self test of gyro from register from 0x36 bit 2 + * + * @param selftest_gyro_u8 : The value of self test of gyro + * + * selftest_gyro_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_gyro( +u8 *selftest_gyro_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page self test of gyro is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro self test */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_GYRO_REG, &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *selftest_gyro_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_SELFTEST_GYRO); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read + * self test of micro controller from register from 0x36 bit 3 + * + * @param selftest_mcu_u8 : The value of self test of micro controller + * + * selftest_mcu_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_mcu( +u8 *selftest_mcu_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page self test of micro controller + is available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the self test of micro controller*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_MCU_REG, &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *selftest_mcu_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_SELFTEST_MCU); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the stat_s8 of + * gyro anymotion interrupt from register from 0x37 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * + * gyro_any_motion_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt can be BNO055_BIT_ENABLE + * by the following APIs + * + * bno055_set_intr_mask_gyro_any_motion() + * + * bno055_set_intr_gyro_any_motion() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_gyro_any_motion( +u8 *gyro_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion interrupt + status is available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro anymotion interrupt stat_s8*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_STAT_GYRO_ANY_MOTION_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_INTR_STAT_GYRO_ANY_MOTION); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the stat_s8 of + * gyro highrate interrupt from register from 0x37 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * + * gyro_highrate_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_gyro_highrate() + * + * bno055_set_intr_gyro_highrate() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_gyro_highrate( +u8 *gyro_highrate_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro highrate interrupt stat_s8*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_STAT_GYRO_HIGHRATE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_INTR_STAT_GYRO_HIGHRATE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the stat_s8 of + * accel highg interrupt from register from 0x37 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * + * accel_high_g_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_high_g() + * + * bno055_set_intr_accel_high_g() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_high_g( +u8 *accel_high_g_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel highg interrupt stat_s8 */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_STAT_ACCEL_HIGH_G_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_high_g_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_INTR_STAT_ACCEL_HIGH_G); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the stat_s8 of + * accel anymotion interrupt from register from 0x37 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * + * accel_any_motion_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_any_motion() + * + * bno055_set_intr_accel_any_motion() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_any_motion( +u8 *accel_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel anymotion interrupt stat_s8 */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_STAT_ACCEL_ANY_MOTION_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_INTR_STAT_ACCEL_ANY_MOTION); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the stat_s8 of + * accel nomotion/slowmotion interrupt from register from 0x37 bit 6 + * + * @param accel_no_motion_u8 : The value of accel + * nomotion/slowmotion interrupt + * + * accel_no_motion_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel nomotion/slowmotion interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_nomotion() + * + * bno055_set_intr_accel_nomotion() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_no_motion( +u8 *accel_no_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel + nomotion/slowmotion interrupt + is available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the stat_s8 of accel + nomotion/slowmotion interrupt*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_STAT_ACCEL_NO_MOTION_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_no_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_INTR_STAT_ACCEL_NO_MOTION); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to read status of main clock + * from the register 0x38 bit 0 + * + * @param stat_main_clk_u8 : the status of main clock + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_stat_main_clk( +u8 *stat_main_clk_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, status of main clk is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the status of main clk */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_MAIN_CLK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *stat_main_clk_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_SYS_MAIN_CLK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to read system status + * code from the register 0x39 it is a byte of data + * + * @param sys_stat_u8 : the status of system + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_stat_code( +u8 *sys_stat_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, the status of system is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the the status of system*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_STAT_CODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sys_stat_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_SYS_STAT_CODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to read system BNO055_ERROR + * code from the register 0x3A it is a byte of data + * + * @param sys_error_u8 : The value of system BNO055_ERROR code + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_error_code( +u8 *sys_error_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, system BNO055_ERROR code is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the system BNO055_ERROR code*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_ERROR_CODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sys_error_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_SYS_ERROR_CODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel unit + * from register from 0x3B bit 0 + * + * @param accel_unit_u8 : The value of accel unit + * + * accel_unit_u8 | result + * ------------- | --------------- + * 0x00 | BNO055_ACCEL_UNIT_MSQ + * 0x01 | BNO055_ACCEL_UNIT_MG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_unit( +u8 *accel_unit_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel unit is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the accel unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_unit_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_ACCEL_UNIT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel unit + * from register from 0x3B bit 0 + * + * @param accel_unit_u8 : The value of accel unit + * + * accel_unit_u8 | result + * ------------- | --------------- + * 0x00 | BNO055_ACCEL_UNIT_MSQ + * 0x01 | BNO055_ACCEL_UNIT_MG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_unit( +u8 accel_unit_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the accel unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_UNIT, accel_unit_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_UNIT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the gyro unit + * from register from 0x3B bit 1 + * + * @param gyro_unit_u8 : The value of accel unit + * + * gyro_unit_u8 | result + * ------------- | ----------- + * 0x00 | BNO055_GYRO_UNIT_DPS + * 0x01 | BNO055_GYRO_UNIT_RPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_unit( +u8 *gyro_unit_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro unit is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the gyro unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_unit_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_GYRO_UNIT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro unit + * from register from 0x3B bit 1 + * + * @param gyro_unit_u8 : The value of accel unit + * + * gyro_unit_u8 | result + * ------------- | ----------- + * 0x00 | BNO055_GYRO_UNIT_DPS + * 0x01 | BNO055_GYRO_UNIT_RPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_unit(u8 gyro_unit_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the gyro unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_UNIT, gyro_unit_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_UNIT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the Euler unit + * from register from 0x3B bit 2 + * + * @param euler_unit_u8 : The value of accel unit + * + * euler_unit_u8 | result + * -------------- | ----------- + * 0x00 | BNO055_EULER_UNIT_DEG + * 0x01 | BNO055_EULER_UNIT_RAD + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_euler_unit( +u8 *euler_unit_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, Euler unit is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the Euler unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *euler_unit_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_EULER_UNIT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the Euler unit + * from register from 0x3B bit 2 + * + * @param euler_unit_u8 : The value of Euler unit + * + * euler_unit_u8 | result + * -------------- | ----------- + * 0x00 | BNO055_EULER_UNIT_DEG + * 0x01 | BNO055_EULER_UNIT_RAD + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_euler_unit(u8 euler_unit_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the Euler unit*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_EULER_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_EULER_UNIT, euler_unit_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_EULER_UNIT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to write the tilt unit + * from register from 0x3B bit 3 + * + * @param tilt_unit_u8 : The value of tilt unit + * + * tilt_unit_u8 | result + * --------------- | --------- + * 0x00 | degrees + * 0x01 | radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_tilt_unit( +u8 *tilt_unit_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, chip id is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TILT_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *tilt_unit_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_TILT_UNIT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the tilt unit + * from register from 0x3B bit 3 + * + * @param tilt_unit_u8 : The value of tilt unit + * + * tilt_unit_u8 | result + * --------------- | --------- + * 0x00 | degrees + * 0x01 | radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + * \return Communication results + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_tilt_unit(u8 tilt_unit_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TILT_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_TILT_UNIT, tilt_unit_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_TILT_UNIT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the temperature unit + * from register from 0x3B bit 4 + * + * @param temp_unit_u8 : The value of temperature unit + * + * temp_unit_u8 | result + * ----------- | -------------- + * 0x00 | BNO055_TEMP_UNIT_CELSIUS + * 0x01 | BNO055_TEMP_UNIT_FAHRENHEIT + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_temp_unit( +u8 *temp_unit_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, temperature unit is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the temperature unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *temp_unit_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_TEMP_UNIT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the temperature unit + * from register from 0x3B bit 4 + * + * @param temp_unit_u8 : The value of temperature unit + * + * temp_unit_u8 | result + * ----------- | -------------- + * 0x00 | BNO055_TEMP_UNIT_CELSIUS + * 0x01 | BNO055_TEMP_UNIT_FAHRENHEIT + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_temp_unit( +u8 temp_unit_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the temperature unit */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_UNIT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_TEMP_UNIT, + temp_unit_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_UNIT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the current selected orientation mode + * from register from 0x3B bit 7 + * + * @param data_output_format_u8 : The value of data output format + * + * data_output_format_u8 | result + * -------------------- | -------- + * 0x00 | Windows + * 0x01 | Android + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_data_output_format( +u8 *data_output_format_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, data output format is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the data output format */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_DATA_OUTPUT_FORMAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_output_format_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_DATA_OUTPUT_FORMAT); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the current selected orientation mode + * from register from 0x3B bit 7 + * + * @param data_output_format_u8 : The value of data output format + * + * data_output_format_u8 | result + * -------------------- | -------- + * 0x00 | Windows + * 0x01 | Android + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_data_output_format( +u8 data_output_format_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the data output format */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_DATA_OUTPUT_FORMAT_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_DATA_OUTPUT_FORMAT, + data_output_format_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_DATA_OUTPUT_FORMAT_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! @brief This API used to read the operation mode + * from register from 0x3D bit 0 to 3 + * + * @param operation_mode_u8 : The value of operation mode + * + * operation_mode_u8 | result | comments + * ----------|----------------------------|---------------------------- + * 0x00 | BNO055_OPERATION_MODE_CONFIG | Configuration mode + * 0x01 | BNO055_OPERATION_MODE_ACCONLY | Reads accel data alone + * 0x02 | BNO055_OPERATION_MODE_MAGONLY | Reads mag data alone + * 0x03 | BNO055_OPERATION_MODE_GYRONLY | Reads gyro data alone + * 0x04 | BNO055_OPERATION_MODE_ACCMAG | Reads accel and mag data + * 0x05 | BNO055_OPERATION_MODE_ACCGYRO | Reads accel and gyro data + * 0x06 | BNO055_OPERATION_MODE_MAGGYRO | Reads accel and mag data + * 0x07 | OPERATION_MODE_ANY_MOTION | Reads accel mag and gyro data + * 0x08 | BNO055_OPERATION_MODE_IMUPLUS | Inertial measurement unit + * - | - | Reads accel,gyro and fusion data + * 0x09 | BNO055_OPERATION_MODE_COMPASS | Reads accel, mag data + * - | - | and fusion data + * 0x0A | BNO055_OPERATION_MODE_M4G | Reads accel, mag data + * - | - | and fusion data + * 0x0B | BNO055_OPERATION_MODE_NDOF_FMC_OFF| Nine degrees of freedom with + * - | - | fast magnetic calibration + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * 0x0C | BNO055_OPERATION_MODE_NDOF | Nine degrees of freedom + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note In the config mode, all sensor and fusion data + * becomes zero and it is mainly derived + * to configure the various settings of the BNO + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_operation_mode( +u8 *operation_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, operation mode is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of operation mode*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *operation_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_OPERATION_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! @brief This API used to write the operation mode + * from register from 0x3D bit 0 to 3 + * + * @param operation_mode_u8 : The value of operation mode + * + * operation_mode_u8 | result | comments + * ---------|-----------------------------------|-------------------------- + * 0x00 | BNO055_OPERATION_MODE_CONFIG | Configuration mode + * 0x01 | BNO055_OPERATION_MODE_ACCONLY | Reads accel data alone + * 0x02 | BNO055_OPERATION_MODE_MAGONLY | Reads mag data alone + * 0x03 | BNO055_OPERATION_MODE_GYRONLY | Reads gyro data alone + * 0x04 | BNO055_OPERATION_MODE_ACCMAG | Reads accel and mag data + * 0x05 | BNO055_OPERATION_MODE_ACCGYRO | Reads accel and gyro data + * 0x06 | BNO055_OPERATION_MODE_MAGGYRO | Reads accel and mag data + * 0x07 | OPERATION_MODE_ANY_MOTION | Reads accel mag and + * | - | gyro data + * 0x08 | BNO055_OPERATION_MODE_IMUPLUS | Inertial measurement unit + * - | | Reads accel,gyro and + * | - | fusion data + * 0x09 | BNO055_OPERATION_MODE_COMPASS | Reads accel, mag data + * - | - | and fusion data + * 0x0A | BNO055_OPERATION_MODE_M4G | Reads accel, mag data + * - | - | and fusion data + * 0x0B | BNO055_OPERATION_MODE_NDOF_FMC_OFF| Nine degrees of freedom with + * - | - | fast magnetic calibration + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * 0x0C | BNO055_OPERATION_MODE_NDOF | Nine degrees of freedom + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note In the config mode, all sensor and fusion data + * becomes zero and it is mainly derived + * to configure the various settings of the BNO + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_operation_mode(u8 operation_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + /* If the previous operation mode is config it is + directly write the operation mode */ + if (prev_opmode_u8 == BNO055_OPERATION_MODE_CONFIG) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_OPERATION_MODE, + operation_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + /* Config mode to other + operation mode switching + required delay of 600ms*/ + p_bno055->delay_msec( + BNO055_MODE_SWITCHING_DELAY); + } + } else { + /* If the previous operation + mode is not config it is + write the config mode */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_OPERATION_MODE, + BNO055_OPERATION_MODE_CONFIG); + com_rslt += bno055_write_register( + BNO055_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + /* other mode to config mode switching + required delay of 20ms*/ + p_bno055->delay_msec( + BNO055_CONFIG_MODE_SWITCHING_DELAY); + } + /* Write the operation mode */ + if (operation_mode_u8 != + BNO055_OPERATION_MODE_CONFIG) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_OPERATION_MODE, + operation_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + /* Config mode to other + operation mode switching + required delay of 600ms*/ + p_bno055->delay_msec( + BNO055_MODE_SWITCHING_DELAY); + } + } + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! @brief This API used to read the power mode + * from register from 0x3E bit 0 to 1 + * + * @param power_mode_u8 : The value of power mode + * + * power_mode_u8| result | comments + * ---------|---------------------------|------------------------------------- + * 0x00 |BNO055_POWER_MODE_NORMAL | In the NORMAL mode the register + * - | - | map and the internal peripherals + * - | - | of the MCU are always + * - | - | operative in this mode + * 0x01 |BNO055_POWER_MODE_LOWPOWER | This is first level of power + * | - | saving mode + * 0x02 |BNO055_POWER_MODE_SUSPEND | In suspend mode the system is + * - | - | paused and all the sensors and + * - | - | the micro controller are + * - | - | put into sleep mode. + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note For detailed about LOWPOWER mode + * refer data sheet 3.4.2 + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_power_mode( +u8 *power_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, power mode is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of power mode */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *power_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_POWER_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! @brief This API used to write the power mode + * from register from 0x3E bit 0 to 1 + * + * @param power_mode_u8 : The value of power mode + * + * + * power_mode_u8| result | comments + * -------|----------------------------|--------------------------------- + * 0x00 | BNO055_POWER_MODE_NORMAL | In the NORMAL mode the register + * - | - | map and the internal peripherals + * - | - | of the MCU are always + * - | - | operative in this mode + * 0x01 | BNO055_POWER_MODE_LOWPOWER | This is first level of power + * | - | saving mode + * 0x02 | BNO055_POWER_MODE_SUSPEND | In suspend mode the system is + * - | - | paused and all the sensors and + * - | - | the micro controller are + * - | - | put into sleep mode. + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note For detailed about LOWPOWER mode + * refer data sheet 3.4.2 + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_power_mode(u8 power_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of power mode */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_POWER_MODE, power_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the reset interrupt + * from register from 0x3F bit 6 + * It resets all the interrupt bit and interrupt output + * + * @param intr_rst_u8 : The value of reset interrupt + * + * intr_rst_u8 | result + * ------------ |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_rst( +u8 *intr_rst_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, reset interrupt is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of reset interrupt*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *intr_rst_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_INTR_RST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the reset interrupt + * from register from 0x3F bit 6 + * It resets all the interrupt bit and interrupt output + * + * @param intr_rst_u8 : The value of reset interrupt + * + * intr_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_rst(u8 intr_rst_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, reset interrupt + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Write the value of reset interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_INTR_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_INTR_RST, intr_rst_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_INTR_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the clk source + * from register from 0x3F bit 7 + * + * @param clk_src_u8 : The value of clk source + * + * clk_src_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_clk_src( +u8 *clk_src_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, clk source is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of clk source */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_CLK_SRC_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *clk_src_u8 = + BNO055_GET_BITSLICE(data_u8r, BNO055_CLK_SRC); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the clk source + * from register from 0x3F bit 7 + * + * @param clk_src_u8 : The value of clk source + * + * clk_src_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_clk_src(u8 clk_src_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, clk source is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Write the value of clk source */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_CLK_SRC_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_CLK_SRC, clk_src_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_CLK_SRC_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the reset system + * from register from 0x3F bit 5 + * + * @param sys_rst_u8 : The value of reset system + * + * sys_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It resets the whole system + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_rst( +u8 *sys_rst_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, reset system is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of reset system */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sys_rst_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_SYS_RST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the reset system + * from register from 0x3F bit 5 + * + * @param sys_rst_u8 : The value of reset system + * + * sys_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It resets the whole system + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_sys_rst(u8 sys_rst_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, reset system is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Write the value of reset system */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SYS_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_SYS_RST, sys_rst_u8); + com_rslt = + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SYS_RST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the self test + * from register from 0x3F bit 0 + * + * @param selftest_u8 : The value of self test + * + * selftest_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It triggers the self test + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest( +u8 *selftest_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, self test is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of self test */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *selftest_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_SELFTEST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the self test + * from register from 0x3F bit 0 + * + * @param selftest_u8 : The value of self test + * + * selftest_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It triggers the self test + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_selftest(u8 selftest_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of self test */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_SELFTEST, + selftest_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SELFTEST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the temperature source + * from register from 0x40 bit 0 and 1 + * + * @param temp_source_u8 : The value of selected temperature source + * + * temp_source_u8 | result + * ---------------- |--------------- + * 0x00 | BNO055_ACCEL_TEMP_EN + * 0X01 | BNO055_GYRO_TEMP_EN + * 0X03 | BNO055_MCU_TEMP_EN + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_temp_source( +u8 *temp_source_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, temperature source is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of temperature source */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_SOURCE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *temp_source_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_TEMP_SOURCE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the temperature source + * from register from 0x40 bit 0 and 1 + * + * @param temp_source_u8 : The value of selected temperature source + * + * temp_source_u8 | result + * ---------------- |--------------- + * 0x00 | BNO055_ACCEL_TEMP_EN + * 0X01 | BNO055_GYRO_TEMP_EN + * 0X03 | BNO055_MCU_TEMP_EN + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_temp_source(u8 temp_source_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of temperature source*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_SOURCE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_TEMP_SOURCE, temp_source_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_TEMP_SOURCE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the axis remap value + * from register from 0x41 bit 0 and 5 + * + * @param remap_axis_u8 : The value of axis remapping + * + * remap_axis_u8 | result | comments + * ------------|-------------------|------------ + * 0X21 | BNO055_REMAP_X_Y | Z=Z;X=Y;Y=X + * 0X18 | BNO055_REMAP_Y_Z | X=X;Y=Z;Z=Y + * 0X06 | BNO055_REMAP_Z_X | Y=Y;X=Z;Z=X + * 0X12 | BNO055_REMAP_X_Y_Z_TYPE0 | X=Z;Y=X;Z=Y + * 0X09 | BNO055_REMAP_X_Y_Z_TYPE1 | X=Y;Y=Z;Z=X + * 0X24 | BNO055_DEFAULT_AXIS | X=X;Y=Y;Z=Z + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : For axis sign remap refer the following APIs + * x-axis : + * + * bno055_set_x_remap_sign() + * + * y-axis : + * + * bno055_set_y_remap_sign() + * + * z-axis : + * + * bno055_set_z_remap_sign() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_axis_remap_value( +u8 *remap_axis_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, axis remap is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of axis remap*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_AXIS_VALUE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *remap_axis_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_REMAP_AXIS_VALUE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the axis remap value + * from register from 0x41 bit 0 and 5 + * + * @param remap_axis_u8 : The value of axis remapping + * + * remap_axis_u8 | result | comments + * ------------|-------------------|------------ + * 0X21 | BNO055_REMAP_X_Y | Z=Z;X=Y;Y=X + * 0X18 | BNO055_REMAP_Y_Z | X=X;Y=Z;Z=Y + * 0X06 | BNO055_REMAP_Z_X | Y=Y;X=Z;Z=X + * 0X12 | BNO055_REMAP_X_Y_Z_TYPE0 | X=Z;Y=X;Z=Y + * 0X09 | BNO055_REMAP_X_Y_Z_TYPE1 | X=Y;Y=Z;Z=X + * 0X24 | BNO055_DEFAULT_AXIS | X=X;Y=Y;Z=Z + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : For axis sign remap refer the following APIs + * x-axis : + * + * bno055_set_x_remap_sign() + * + * y-axis : + * + * bno055_set_y_remap_sign() + * + * z-axis : + * + * bno055_set_z_remap_sign() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_axis_remap_value( +u8 remap_axis_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + /* Write the value of axis remap */ + if (stat_s8 == BNO055_SUCCESS) { + switch (remap_axis_u8) { + case BNO055_REMAP_X_Y: + case BNO055_REMAP_Y_Z: + case BNO055_REMAP_Z_X: + case BNO055_REMAP_X_Y_Z_TYPE0: + case BNO055_REMAP_X_Y_Z_TYPE1: + case BNO055_DEFAULT_AXIS: + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_AXIS_VALUE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_REMAP_AXIS_VALUE, + remap_axis_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_AXIS_VALUE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + default: + /* Write the default axis remap value */ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_AXIS_VALUE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_REMAP_AXIS_VALUE, + BNO055_DEFAULT_AXIS); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_AXIS_VALUE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the x-axis remap + * sign from register from 0x42 bit 2 + * + * @param remap_x_sign_u8 : The value of x-axis remap sign + * + * remap_x_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_x_sign( +u8 *remap_x_sign_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, x-axis remap sign is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of x-axis remap sign */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_X_SIGN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *remap_x_sign_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_REMAP_X_SIGN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the x-axis remap + * sign from register from 0x42 bit 2 + * + * @param remap_x_sign_u8 : The value of x-axis remap sign + * + * remap_x_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_x_sign( +u8 remap_x_sign_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of x-axis remap */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_X_SIGN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_REMAP_X_SIGN, + remap_x_sign_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_X_SIGN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the y-axis remap + * sign from register from 0x42 bit 1 + * + * @param remap_y_sign_u8 : The value of y-axis remap sign + * + * remap_y_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_y_sign( +u8 *remap_y_sign_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, y-axis remap sign is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of y-axis remap sign*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Y_SIGN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *remap_y_sign_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_REMAP_Y_SIGN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the y-axis remap + * sign from register from 0x42 bit 1 + * + * @param remap_y_sign_u8 : The value of y-axis remap sign + * + * remap_y_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_y_sign( +u8 remap_y_sign_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of y-axis remap sign*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Y_SIGN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_REMAP_Y_SIGN, + remap_y_sign_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Y_SIGN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the z-axis remap + * sign from register from 0x42 bit 0 + * + * @param remap_z_sign_u8 : The value of z-axis remap sign + * + * remap_z_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_z_sign( +u8 *remap_z_sign_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, z-axis remap sign is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read the value of z-axis remap sign*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Z_SIGN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *remap_z_sign_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_REMAP_Z_SIGN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the z-axis remap + * sign from register from 0x42 bit 0 + * + * @param remap_z_sign_u8 : The value of z-axis remap sign + * + * remap_z_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_z_sign( +u8 remap_z_sign_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write the value of z-axis remap sign*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Z_SIGN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_REMAP_Z_SIGN, + remap_z_sign_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_REMAP_Z_SIGN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API is used to read soft iron calibration matrix + * from the register 0x43 to 0x53 it is a 18 bytes of data + * + * @param sic_matrix : The value of soft iron calibration matrix + * + * sic_matrix | result + * --------------------|---------------------------------- + * sic_0 | soft iron calibration matrix zero + * sic_1 | soft iron calibration matrix one + * sic_2 | soft iron calibration matrix two + * sic_3 | soft iron calibration matrix three + * sic_4 | soft iron calibration matrix four + * sic_5 | soft iron calibration matrix five + * sic_6 | soft iron calibration matrix six + * sic_7 | soft iron calibration matrix seven + * sic_8 | soft iron calibration matrix eight + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : Each soft iron calibration matrix range from -32768 to +32767 + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_sic_matrix( +struct bno055_sic_matrix_t *sic_matrix) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the soft iron calibration matrix values + data_u8[BNO055_SOFT_IRON_CALIB_0_LSB] - sic_0->LSB + data_u8[BNO055_SOFT_IRON_CALIB_0_MSB] - sic_0->MSB + data_u8[BNO055_SOFT_IRON_CALIB_1_LSB] - sic_1->LSB + data_u8[BNO055_SOFT_IRON_CALIB_1_MSB] - sic_1->MSB + data_u8[BNO055_SOFT_IRON_CALIB_2_LSB] - sic_2->LSB + data_u8[BNO055_SOFT_IRON_CALIB_2_MSB] - sic_2->MSB + data_u8[BNO055_SOFT_IRON_CALIB_3_LSB] - sic_3->LSB + data_u8[BNO055_SOFT_IRON_CALIB_3_MSB] - sic_3->MSB + data_u8[BNO055_SOFT_IRON_CALIB_4_LSB] - sic_4->LSB + data_u8[BNO055_SOFT_IRON_CALIB_4_MSB] - sic_4->MSB + data_u8[BNO055_SOFT_IRON_CALIB_5_LSB] - sic_5->LSB + data_u8[BNO055_SOFT_IRON_CALIB_5_MSB] - sic_5->MSB + data_u8[BNO055_SOFT_IRON_CALIB_6_LSB] - sic_6->LSB + data_u8[BNO055_SOFT_IRON_CALIB_6_MSB] - sic_6->MSB + data_u8[BNO055_SOFT_IRON_CALIB_7_LSB] - sic_7->LSB + data_u8[BNO055_SOFT_IRON_CALIB_7_MSB] - sic_7->MSB + data_u8[BNO055_SOFT_IRON_CALIB_8_LSB] - sic_8->LSB + data_u8[BNO055_SOFT_IRON_CALIB_8_MSB] - sic_8->MSB + */ + u8 data_u8[BNO055_SOFT_IRON_CALIBRATION_MATRIX_SIZE] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, soft iron calibration matrix is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read soft iron calibration matrix value + it is eighteen bytes of data */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_0_LSB_REG, + data_u8, BNO055_SOFT_IRON_CALIBRATION_MATRIX_SIZE); + if (com_rslt == BNO055_SUCCESS) { + /*soft iron calibration matrix zero*/ + data_u8[BNO055_SOFT_IRON_CALIB_0_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_0_LSB], + BNO055_SIC_MATRIX_0_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_0_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_0_MSB], + BNO055_SIC_MATRIX_0_MSB); + sic_matrix->sic_0 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_0_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SOFT_IRON_CALIB_0_LSB])); + + /*soft iron calibration matrix one*/ + data_u8[BNO055_SOFT_IRON_CALIB_1_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_1_LSB], + BNO055_SIC_MATRIX_1_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_1_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_1_MSB], + BNO055_SIC_MATRIX_1_MSB); + sic_matrix->sic_1 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_1_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SOFT_IRON_CALIB_1_LSB])); + + /*soft iron calibration matrix two*/ + data_u8[BNO055_SOFT_IRON_CALIB_2_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_2_LSB], + BNO055_SIC_MATRIX_2_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_2_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_2_MSB], + BNO055_SIC_MATRIX_2_MSB); + sic_matrix->sic_2 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_2_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SOFT_IRON_CALIB_2_LSB])); + + /*soft iron calibration matrix three*/ + data_u8[BNO055_SOFT_IRON_CALIB_3_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_3_LSB], + BNO055_SIC_MATRIX_3_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_3_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_3_MSB], + BNO055_SIC_MATRIX_3_LSB); + sic_matrix->sic_3 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_3_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_3_LSB])); + + /*soft iron calibration matrix four*/ + data_u8[BNO055_SOFT_IRON_CALIB_4_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_4_LSB], + BNO055_SIC_MATRIX_4_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_4_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_4_MSB], + BNO055_SIC_MATRIX_4_LSB); + sic_matrix->sic_4 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_4_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_4_LSB])); + + /*soft iron calibration matrix five*/ + data_u8[BNO055_SOFT_IRON_CALIB_5_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_5_LSB], + BNO055_SIC_MATRIX_5_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_5_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_5_MSB], + BNO055_SIC_MATRIX_5_LSB); + sic_matrix->sic_5 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_5_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_5_LSB])); + + /*soft iron calibration matrix six*/ + data_u8[BNO055_SOFT_IRON_CALIB_6_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_6_LSB], + BNO055_SIC_MATRIX_6_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_6_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_6_MSB], + BNO055_SIC_MATRIX_6_LSB); + sic_matrix->sic_6 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_6_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_6_LSB])); + + /*soft iron calibration matrix seven*/ + data_u8[BNO055_SOFT_IRON_CALIB_7_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_7_LSB], + BNO055_SIC_MATRIX_7_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_7_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_7_MSB], + BNO055_SIC_MATRIX_7_LSB); + sic_matrix->sic_7 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_7_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_7_LSB])); + + /*soft iron calibration matrix eight*/ + data_u8[BNO055_SOFT_IRON_CALIB_8_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_8_LSB], + BNO055_SIC_MATRIX_8_LSB); + data_u8[BNO055_SOFT_IRON_CALIB_8_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SOFT_IRON_CALIB_8_MSB], + BNO055_SIC_MATRIX_8_LSB); + sic_matrix->sic_8 = (s16)((((s32) + (s8)(data_u8[BNO055_SOFT_IRON_CALIB_8_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SOFT_IRON_CALIB_8_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to write soft iron calibration matrix + * from the register 0x43 to 0x53 it is a 18 bytes of data + * + * @param sic_matrix : The value of soft iron calibration matrix + * + * sic_matrix | result + * --------------------|---------------------------------- + * sic_0 | soft iron calibration matrix zero + * sic_1 | soft iron calibration matrix one + * sic_2 | soft iron calibration matrix two + * sic_3 | soft iron calibration matrix three + * sic_4 | soft iron calibration matrix four + * sic_5 | soft iron calibration matrix five + * sic_6 | soft iron calibration matrix six + * sic_7 | soft iron calibration matrix seven + * sic_8 | soft iron calibration matrix eight + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : Each soft iron calibration matrix range from -32768 to +32767 + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_sic_matrix( +struct bno055_sic_matrix_t *sic_matrix) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data1_u8r = BNO055_INIT_VALUE; +u8 data2_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* write soft iron calibration + matrix zero value*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_0_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_0 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_0_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_0_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_0_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_0 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_0_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_0_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix one value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_1_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_1 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_1_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_1_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_1_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_1 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_1_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_1_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix two value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_2_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_2 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_2_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_2_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_2_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_2 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_2_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_2_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix three value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_3_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_3 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_3_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_3_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_3_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_3 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_3_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_3_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix four value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_4_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_4 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_4_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_4_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_4_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_4 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_4_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_4_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix five value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_5_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_5 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_5_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_5_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_5_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_5 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_5_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_5_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix six value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_6_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_6 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_6_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_6_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_6_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_6 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_6_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_6_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix seven value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_7_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_7 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_7_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_7_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_7_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_7 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_7_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_7_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write soft iron calibration + matrix eight value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_8_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_8 + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_8_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_8_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_8_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (sic_matrix->sic_8 >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_SIC_MATRIX_8_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_SIC_MATRIX_8_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API is used to read accel offset and accel radius + * offset form register 0x55 to 0x5A and radius form 0x67 and 0x68 + * + * @param accel_offset : The value of accel offset and radius + * + * bno055_accel_offset_t | result + * ------------------- | ---------------- + * x | accel offset x + * y | accel offset y + * z | accel offset z + * r | accel offset r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the accel offset varies based on + * the G-range of accel sensor. + * + * accel G range | offset range + * --------------- | -------------- + * BNO055_ACCEL_RANGE_2G | +/-2000 + * BNO055_ACCEL_RANGE_4G | +/-4000 + * BNO055_ACCEL_RANGE_8G | +/-8000 + * BNO055_ACCEL_RANGE_16G | +/-16000 + * + * accel G range can be configured by using the + * bno055_set_accel_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_offset( +struct bno055_accel_offset_t *accel_offset) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the accel offset values + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] - offset x->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] - offset x->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] - offset y->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] - offset y->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] - offset z->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] - offset z->MSB + */ + u8 data_u8[BNO055_ACCEL_OFFSET_ARRAY] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel offset is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read accel offset value it is six bytes of data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_X_LSB_REG, + data_u8, BNO055_ACCEL_OFFSET_ARRAY); + if (com_rslt == BNO055_SUCCESS) { + /* Read accel x offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB], + BNO055_ACCEL_OFFSET_X_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB], + BNO055_ACCEL_OFFSET_X_MSB); + accel_offset->x = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB])); + + /* Read accel y offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB], + BNO055_ACCEL_OFFSET_Y_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB], + BNO055_ACCEL_OFFSET_Y_MSB); + accel_offset->y = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB])); + + /* Read accel z offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB], + BNO055_ACCEL_OFFSET_Z_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB], + BNO055_ACCEL_OFFSET_Z_MSB); + accel_offset->z = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB])); + + /* Read accel radius value + it is two bytes of data*/ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RADIUS_LSB_REG, + data_u8, + BNO055_LSB_MSB_READ_LENGTH); + /* Array holding the accel radius values + data_u8[BNO055_OFFSET_RADIUS_LSB] - radius->LSB + data_u8[BNO055_OFFSET_RADIUS_MSB] - radius->MSB + */ + if (com_rslt == BNO055_SUCCESS) { + data_u8[BNO055_OFFSET_RADIUS_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_OFFSET_RADIUS_LSB], + BNO055_ACCEL_RADIUS_LSB); + data_u8[BNO055_OFFSET_RADIUS_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_OFFSET_RADIUS_MSB], + BNO055_ACCEL_RADIUS_MSB); + accel_offset->r = (s16)((((s32)(s8) + (data_u8[BNO055_OFFSET_RADIUS_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_OFFSET_RADIUS_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to write accel offset and accel radius + * offset form register 0x55 to 0x5A and radius form 0x67 and 0x68 + * + * @param accel_offset : The value of accel offset and radius + * + * bno055_accel_offset_t | result + * ------------------- | ---------------- + * x | accel offset x + * y | accel offset y + * z | accel offset z + * r | accel offset r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the accel offset varies based on + * the G-range of accel sensor. + * + * accel G range | offset range + * --------------- | -------------- + * BNO055_ACCEL_RANGE_2G | +/-2000 + * BNO055_ACCEL_RANGE_4G | +/-4000 + * BNO055_ACCEL_RANGE_8G | +/-8000 + * BNO055_ACCEL_RANGE_16G | +/-16000 + * + * accel G range can be configured by using the + * bno055_set_accel_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_accel_offset( +struct bno055_accel_offset_t *accel_offset) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data1_u8r = BNO055_INIT_VALUE; +u8 data2_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* write accel offset x value*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->x + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_X_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->x >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_X_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write accel offset y value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->y + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_Y_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->y >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_Y_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + /* write accel offset z value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->z + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_Z_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->z >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_OFFSET_Z_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /*write accel radius value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RADIUS_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->r + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_RADIUS_LSB, + data1_u8r); + com_rslt = + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RADIUS_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RADIUS_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (accel_offset->r >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_ACCEL_RADIUS_MSB, + data1_u8r); + com_rslt = + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RADIUS_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} + +/*! + * @brief This API is used to read mag offset + * offset form register 0x69 to 0x6A + * + * @param mag_offset : The value of mag offset and radius + * + * bno055_mag_offset_t | result + * ------------------- | ---------------- + * x | mag offset x + * y | mag offset y + * z | mag offset z + * r | mag radius r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the magnetometer offset is +/-6400 in LSB + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_offset( +struct bno055_mag_offset_t *mag_offset) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the mag offset values + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] - offset x->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] - offset x->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] - offset y->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] - offset y->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] - offset z->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] - offset z->MSB + */ + u8 data_u8[BNO055_MAG_OFFSET_ARRAY] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, mag offset is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read mag offset value it the six bytes of data */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_X_LSB_REG, + data_u8, BNO055_MAG_OFFSET_ARRAY); + if (com_rslt == BNO055_SUCCESS) { + /* Read mag x offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB], + BNO055_MAG_OFFSET_X_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB], + BNO055_MAG_OFFSET_X_MSB); + mag_offset->x = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB])); + + /* Read mag y offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB], + BNO055_MAG_OFFSET_Y_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB], + BNO055_MAG_OFFSET_Y_MSB); + mag_offset->y = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB])); + + /* Read mag z offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB], + BNO055_MAG_OFFSET_Z_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB], + BNO055_MAG_OFFSET_Z_MSB); + mag_offset->z = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) + | (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB])); + + /* Read mag radius value + it the two bytes of data */ + com_rslt += p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_RADIUS_LSB_REG, + data_u8, + BNO055_LSB_MSB_READ_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Array holding the mag radius values + data_u8[BNO055_OFFSET_RADIUS_LSB] - + radius->LSB + data_u8[BNO055_OFFSET_RADIUS_MSB] - + radius->MSB + */ + data_u8[BNO055_OFFSET_RADIUS_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_OFFSET_RADIUS_LSB], + BNO055_MAG_RADIUS_LSB); + data_u8[BNO055_OFFSET_RADIUS_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_OFFSET_RADIUS_MSB], + BNO055_MAG_RADIUS_MSB); + mag_offset->r = (s16)((((s32)(s8) + (data_u8[BNO055_OFFSET_RADIUS_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_OFFSET_RADIUS_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} + +/*! + * @brief This API is used to read mag offset + * offset form register 0x69 to 0x6A + * + * @param mag_offset : The value of mag offset and radius + * + * bno055_mag_offset_t | result + * ------------------- | ---------------- + * x | mag offset x + * y | mag offset y + * z | mag offset z + * r | mag radius r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the magnetometer offset is +/-6400 in LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_mag_offset( +struct bno055_mag_offset_t *mag_offset) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data1_u8r = BNO055_INIT_VALUE; +u8 data2_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* write Mag offset x value*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->x + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_X_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->x >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_X_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write Mag offset y value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->y & + BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_Y_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->y >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_Y_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + /* write Mag offset z value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->z & + BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_Z_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->z >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_OFFSET_Z_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write Mag radius value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_RADIUS_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->r & + BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_RADIUS_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_RADIUS_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_RADIUS_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (mag_offset->r >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_MAG_RADIUS_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_RADIUS_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API is used to read gyro offset + * offset form register 0x61 to 0x66 + * + * @param gyro_offset : The value of gyro offset + * + * bno055_gyro_offset_t | result + * ------------------- | ---------------- + * x | gyro offset x + * y | gyro offset y + * z | gyro offset z + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the gyro offset varies based on + * the range of gyro sensor + * + * gyro G range | offset range + * -------------------- | ------------ + * BNO055_GYRO_RANGE_2000DPS | +/-32000 + * BNO055_GYRO_RANGE_1000DPS | +/-16000 + * BNO055_GYRO_RANGE_500DPS | +/-8000 + * BNO055_GYRO_RANGE_250DPS | +/-4000 + * BNO055_GYRO_RANGE_125DPS | +/-2000 + * + * Gyro range can be configured by using the + * bno055_set_gyro_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_offset( +struct bno055_gyro_offset_t *gyro_offset) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + /* Array holding the gyro offset values + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] - offset x->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] - offset x->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] - offset y->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] - offset y->MSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] - offset z->LSB + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] - offset z->MSB + */ + u8 data_u8[BNO055_GYRO_OFFSET_ARRAY] = { + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE, + BNO055_INIT_VALUE, BNO055_INIT_VALUE}; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro offset is + available in the page zero*/ + if (p_bno055->page_id != BNO055_PAGE_ZERO) + /* Write the page zero*/ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ZERO); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ZERO)) { + /* Read gyro offset value it the six bytes of data*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_X_LSB_REG, + data_u8, BNO055_GYRO_OFFSET_ARRAY); + if (com_rslt == BNO055_SUCCESS) { + /* Read gyro x offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB], + BNO055_GYRO_OFFSET_X_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB], + BNO055_GYRO_OFFSET_X_MSB); + gyro_offset->x = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_X_LSB])); + + /* Read gyro y offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB], + BNO055_GYRO_OFFSET_Y_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB], + BNO055_GYRO_OFFSET_Y_MSB); + gyro_offset->y = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_Y_LSB])); + + /* Read gyro z offset value*/ + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB], + BNO055_GYRO_OFFSET_Z_LSB); + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB] = + BNO055_GET_BITSLICE( + data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB], + BNO055_GYRO_OFFSET_Z_MSB); + gyro_offset->z = (s16)((((s32)(s8) + (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_MSB])) << + (BNO055_SHIFT_EIGHT_BITS)) | + (data_u8[BNO055_SENSOR_OFFSET_DATA_Z_LSB])); + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API is used to read gyro offset + * offset form register 0x61 to 0x66 + * + * @param gyro_offset : The value of gyro offset + * + * bno055_gyro_offset_t | result + * ------------------- | ---------------- + * x | gyro offset x + * y | gyro offset y + * z | gyro offset z + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the gyro offset varies based on + * the range of gyro sensor + * + * gyro G range | offset range + * -------------------- | ------------ + * BNO055_GYRO_RANGE_2000DPS | +/-32000 + * BNO055_GYRO_RANGE_1000DPS | +/-16000 + * BNO055_GYRO_RANGE_500DPS | +/-8000 + * BNO055_GYRO_RANGE_250DPS | +/-4000 + * BNO055_GYRO_RANGE_125DPS | +/-2000 + * + * Gyro range can be configured by using the + * bno055_set_gyro_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_gyro_offset( +struct bno055_gyro_offset_t *gyro_offset) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data1_u8r = BNO055_INIT_VALUE; +u8 data2_u8r = BNO055_INIT_VALUE; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* write gryo offset x value*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->x + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_X_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_X_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->x >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_X_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_X_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + /* write gryo offset y value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->y + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_Y_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Y_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->y >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_Y_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Y_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + /* write gryo offset z value*/ + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->z + & BNO055_SIC_HEX_0_0_F_F_DATA)); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_Z_LSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Z_LSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + + com_rslt += + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data1_u8r = ((s8) + (gyro_offset->z >> + BNO055_SHIFT_EIGHT_BITS) + & BNO055_SIC_HEX_0_0_F_F_DATA); + data2_u8r = + BNO055_SET_BITSLICE(data2_u8r, + BNO055_GYRO_OFFSET_Z_MSB, + data1_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_OFFSET_Z_MSB_REG, + &data2_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/********************************************************/ + /************** PAGE1 Functions *********************/ +/********************************************************/ +/*! + * @brief This API used to read the accel range + * from page one register from 0x08 bit 0 and 1 + * + * @param accel_range_u8 : The value of accel range + * accel_range_u8 | result + * ----------------- | -------------- + * 0x00 | BNO055_ACCEL_RANGE_2G + * 0x01 | BNO055_ACCEL_RANGE_4G + * 0x02 | BNO055_ACCEL_RANGE_8G + * 0x03 | BNO055_ACCEL_RANGE_16G + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_range( +u8 *accel_range_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel g range */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RANGE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_range_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_RANGE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel range + * from page one register from 0x08 bit 0 and 1 + * + * @param accel_range_u8 : The value of accel range + * + * accel_range_u8 | result + * ----------------- | -------------- + * 0x00 | BNO055_ACCEL_RANGE_2G + * 0x01 | BNO055_ACCEL_RANGE_4G + * 0x02 | BNO055_ACCEL_RANGE_8G + * 0x03 | BNO055_ACCEL_RANGE_16G + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_range( +u8 accel_range_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (accel_range_u8 < BNO055_ACCEL_RANGE) { + /* Write the value of accel range*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RANGE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_RANGE, + accel_range_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_RANGE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel bandwidth + * from page one register from 0x08 bit 2 to 4 + * + * @param accel_bw_u8 : The value of accel bandwidth + * + * accel_bw_u8 | result + * ----------------- | --------------- + * 0x00 | BNO055_ACCEL_BW_7_81HZ + * 0x01 | BNO055_ACCEL_BW_15_63HZ + * 0x02 | BNO055_ACCEL_BW_31_25HZ + * 0x03 | BNO055_ACCEL_BW_62_5HZ + * 0x04 | BNO055_ACCEL_BW_125HZ + * 0x05 | BNO055_ACCEL_BW_250HZ + * 0x06 | BNO055_ACCEL_BW_500HZ + * 0x07 | BNO055_ACCEL_BW_1000HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_bw( +u8 *accel_bw_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel bandwidth is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel bandwidth */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_BW_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_bw_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_BW); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel bandwidth + * from page one register from 0x08 bit 2 to 4 + * + * @param accel_bw_u8 : The value of accel bandwidth + * + * accel_bw_u8 | result + * ----------------- | --------------- + * 0x00 | BNO055_ACCEL_BW_7_81HZ + * 0x01 | BNO055_ACCEL_BW_15_63HZ + * 0x02 | BNO055_ACCEL_BW_31_25HZ + * 0x03 | BNO055_ACCEL_BW_62_5HZ + * 0x04 | BNO055_ACCEL_BW_125HZ + * 0x05 | BNO055_ACCEL_BW_250HZ + * 0x06 | BNO055_ACCEL_BW_500HZ + * 0x07 | BNO055_ACCEL_BW_1000HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_bw( +u8 accel_bw_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (accel_bw_u8 < + BNO055_ACCEL_GYRO_BW_RANGE) { + /* Write the accel */ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_BW_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, BNO055_ACCEL_BW, + accel_bw_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_BW_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel power mode + * from page one register from 0x08 bit 5 to 7 + * + * @param accel_power_mode_u8 : The value of accel power mode + * accel_power_mode_u8 | result + * ----------------- | ------------- + * 0x00 | BNO055_ACCEL_NORMAL + * 0x01 | BNO055_ACCEL_SUSPEND + * 0x02 | BNO055_ACCEL_LOWPOWER_1 + * 0x03 | BNO055_ACCEL_STANDBY + * 0x04 | BNO055_ACCEL_LOWPOWER_2 + * 0x05 | BNO055_ACCEL_DEEPSUSPEND + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_power_mode( +u8 *accel_power_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel power mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel bandwidth */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_power_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_POWER_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel power mode + * from page one register from 0x08 bit 5 to 7 + * + * @param accel_power_mode_u8 : The value of accel power mode + * accel_power_mode_u8 | result + * ----------------- | ------------- + * 0x00 | BNO055_ACCEL_NORMAL + * 0x01 | BNO055_ACCEL_SUSPEND + * 0x02 | BNO055_ACCEL_LOWPOWER_1 + * 0x03 | BNO055_ACCEL_STANDBY + * 0x04 | BNO055_ACCEL_LOWPOWER_2 + * 0x05 | BNO055_ACCEL_DEEPSUSPEND + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_power_mode( +u8 accel_power_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (accel_power_mode_u8 < + BNO055_ACCEL_POWER_MODE_RANGE) { + /* Write the value of accel bandwidth*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_POWER_MODE, + accel_power_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the mag output data rate + * from page one register from 0x09 bit 0 to 2 + * + * @param mag_data_output_rate_u8 : The value of mag output data rate + * + * mag_data_output_rate_u8 | result + * ---------------------- |---------------------- + * 0x00 | MAG_DATA_OUTPUT_RATE_2HZ + * 0x01 | MAG_DATA_OUTPUT_RATE_6HZ + * 0x02 | MAG_DATA_OUTPUT_RATE_8HZ + * 0x03 | MAG_DATA_OUTPUT_RATE_10HZ + * 0x04 | MAG_DATA_OUTPUT_RATE_15HZ + * 0x05 | MAG_DATA_OUTPUT_RATE_20HZ + * 0x06 | MAG_DATA_OUTPUT_RATE_25HZ + * 0x07 | MAG_DATA_OUTPUT_RATE_30HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_data_output_rate( +u8 *mag_data_output_rate_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, output data rate + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the mag output data rate*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_OUTPUT_RATE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *mag_data_output_rate_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_DATA_OUTPUT_RATE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the mag output data rate + * from page one register from 0x09 bit 0 to 2 + * + * @param mag_data_output_rate_u8 : The value of mag output data rate + * + * mag_data_output_rate_u8 | result + * ---------------------- |---------------------- + * 0x00 | MAG_DATA_OUTPUT_RATE_2HZ + * 0x01 | MAG_DATA_OUTPUT_RATE_6HZ + * 0x02 | MAG_DATA_OUTPUT_RATE_8HZ + * 0x03 | MAG_DATA_OUTPUT_RATE_10HZ + * 0x04 | MAG_DATA_OUTPUT_RATE_15HZ + * 0x05 | MAG_DATA_OUTPUT_RATE_20HZ + * 0x06 | MAG_DATA_OUTPUT_RATE_25HZ + * 0x07 | MAG_DATA_OUTPUT_RATE_30HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_data_output_rate( +u8 mag_data_output_rate_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (mag_data_output_rate_u8 + < BNO055_MAG_OUTPUT_RANGE) { + /* Write the value of + mag output data rate*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_OUTPUT_RATE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_MAG_DATA_OUTPUT_RATE, + mag_data_output_rate_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_DATA_OUTPUT_RATE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { +com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the mag operation mode + * from page one register from 0x09 bit 3 to 4 + * + * @param mag_operation_mode_u8 : The value of mag operation mode + * + * mag_operation_mode_u8 | result + * ------------------------- |-------------------------- + * 0x00 | MAG_OPR_MODE_LOWPOWER + * 0x01 | MAG_OPR_MODE_REGULAR + * 0x02 | MAG_OPR_MODE_ENHANCED_REGULAR + * 0x03 | MAG_OPR_MODE_HIGH_ACCURACY + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_operation_mode( +u8 *mag_operation_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, mag operation mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of mag operation mode*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OPERATION_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *mag_operation_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_OPERATION_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the mag operation mode + * from page one register from 0x09 bit 3 to 4 + * + * @param mag_operation_mode_u8 : The value of mag operation mode + * + * mag_operation_mode_u8 | result + * ------------------------- |-------------------------- + * 0x00 | MAG_OPR_MODE_LOWPOWER + * 0x01 | MAG_OPR_MODE_REGULAR + * 0x02 | MAG_OPR_MODE_ENHANCED_REGULAR + * 0x03 | MAG_OPR_MODE_HIGH_ACCURACY + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_operation_mode( +u8 mag_operation_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (mag_operation_mode_u8 + < BNO055_MAG_OPR_MODE_RANGE) { + /* Write the value + of mag operation mode*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_MAG_OPERATION_MODE, + mag_operation_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_OPERATION_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the mag power mode + * from page one register from 0x09 bit 4 to 6 + * + * @param mag_power_mode_u8 : The value of mag power mode + * + * mag_power_mode_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_MAG_POWER_MODE_NORMAL + * 0x01 | BNO055_MAG_POWER_MODE_SLEEP + * 0x02 | BNO055_MAG_POWER_MODE_SUSPEND + * 0x03 | BNO055_MAG_POWER_MODE_FORCE_MODE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_power_mode( +u8 *mag_power_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, mag power mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of mag power mode */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *mag_power_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_POWER_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the mag power mode + * from page one register from 0x09 bit 4 to 6 + * + * @param mag_power_mode_u8 : The value of mag power mode + * + * mag_power_mode_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_MAG_POWER_MODE_NORMAL + * 0x01 | BNO055_MAG_POWER_MODE_SLEEP + * 0x02 | BNO055_MAG_POWER_MODE_SUSPEND + * 0x03 | BNO055_MAG_POWER_MODE_FORCE_MODE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_power_mode( +u8 mag_power_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode( + BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (mag_power_mode_u8 < + BNO055_MAG_POWER_MODE_RANGE) { + /* Write the value of mag power mode*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_MAG_POWER_MODE, + mag_power_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { + com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro range + * from page one register from 0x0A bit 0 to 3 + * + * @param gyro_range_u8 : The value of gyro range + * + * gyro_range_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_RANGE_2000DPS + * 0x01 | BNO055_GYRO_RANGE_1000DPS + * 0x02 | BNO055_GYRO_RANGE_500DPS + * 0x03 | BNO055_GYRO_RANGE_250DPS + * 0x04 | BNO055_GYRO_RANGE_125DPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_range( +u8 *gyro_range_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro range */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_RANGE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_range_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_RANGE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro range + * from page one register from 0x0A bit 0 to 3 + * + * @param gyro_range_u8 : The value of gyro range + * + * gyro_range_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_RANGE_2000DPS + * 0x01 | BNO055_GYRO_RANGE_1000DPS + * 0x02 | BNO055_GYRO_RANGE_500DPS + * 0x03 | BNO055_GYRO_RANGE_250DPS + * 0x04 | BNO055_GYRO_RANGE_125DPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_range( +u8 gyro_range_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (gyro_range_u8 < BNO055_GYRO_RANGE) { + /* Write the value of gyro range*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_RANGE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_RANGE, + gyro_range_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_RANGE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro bandwidth + * from page one register from 0x0A bit 3 to 5 + * + * @param gyro_bw_u8 : The value of gyro bandwidth + * + * gyro_bw_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_BW_523HZ + * 0x01 | BNO055_GYRO_BW_230HZ + * 0x02 | BNO055_GYRO_BW_116HZ + * 0x03 | BNO055_GYRO_BW_47HZ + * 0x04 | BNO055_GYRO_BW_23HZ + * 0x05 | BNO055_GYRO_BW_12HZ + * 0x06 | BNO055_GYRO_BW_64HZ + * 0x07 | BNO055_GYRO_BW_32HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_bw( +u8 *gyro_bw_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro bandwidth is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_BW_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_bw_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_BW); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro bandwidth + * from page one register from 0x0A bit 3 to 5 + * + * @param gyro_bw_u8 : The value of gyro bandwidth + * + * gyro_bw_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_BW_523HZ + * 0x01 | BNO055_GYRO_BW_230HZ + * 0x02 | BNO055_GYRO_BW_116HZ + * 0x03 | BNO055_GYRO_BW_47HZ + * 0x04 | BNO055_GYRO_BW_23HZ + * 0x05 | BNO055_GYRO_BW_12HZ + * 0x06 | BNO055_GYRO_BW_64HZ + * 0x07 | BNO055_GYRO_BW_32HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_bw( +u8 gyro_bw_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 gyro_opmode = BNO055_INIT_VALUE; +u8 gyro_auto_sleep_durn = BNO055_INIT_VALUE; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of gyro bandwidth */ + if ((gyro_bw_u8 == BNO055_INIT_VALUE || + gyro_bw_u8 > BNO055_INIT_VALUE) && + gyro_bw_u8 < BNO055_ACCEL_GYRO_BW_RANGE) { + switch (gyro_bw_u8) { + case BNO055_GYRO_BW_523HZ: + gyro_bw_u8 = BNO055_GYRO_BW_523HZ; + break; + case BNO055_GYRO_BW_230HZ: + gyro_bw_u8 = BNO055_GYRO_BW_230HZ; + break; + case BNO055_GYRO_BW_116HZ: + gyro_bw_u8 = BNO055_GYRO_BW_116HZ; + break; + case BNO055_GYRO_BW_47HZ: + gyro_bw_u8 = BNO055_GYRO_BW_47HZ; + break; + case BNO055_GYRO_BW_23HZ: + gyro_bw_u8 = BNO055_GYRO_BW_23HZ; + break; + case BNO055_GYRO_BW_12HZ: + gyro_bw_u8 = BNO055_GYRO_BW_12HZ; + break; + case BNO055_GYRO_BW_64HZ: + gyro_bw_u8 = BNO055_GYRO_BW_64HZ; + break; + case BNO055_GYRO_BW_32HZ: + gyro_bw_u8 = BNO055_GYRO_BW_32HZ; + break; + default: + break; + } + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_BW_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_BW, + gyro_bw_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_BW_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + com_rslt = bno055_get_gyro_power_mode + (&gyro_opmode); + if (com_rslt == BNO055_SUCCESS) { + if (gyro_opmode == + BNO055_GYRO_POWER_MODE_ADVANCE_POWERSAVE) { + com_rslt += + bno055_get_gyro_auto_sleep_durn + (&gyro_auto_sleep_durn); + if (com_rslt == BNO055_SUCCESS) { + com_rslt += + bno055_gyro_set_auto_sleep_durn + (gyro_auto_sleep_durn, + gyro_bw_u8); + } + } + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { +com_rslt = BNO055_ERROR; +} +} else { +com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro power mode + * from page one register from 0x0B bit 0 to 2 + * + * @param gyro_power_mode_u8 : The value of gyro power mode + * + * gyro_power_mode_u8 | result + * ----------------------|---------------------------- + * 0x00 | GYRO_OPR_MODE_NORMAL + * 0x01 | GYRO_OPR_MODE_FASTPOWERUP + * 0x02 | GYRO_OPR_MODE_DEEPSUSPEND + * 0x03 | GYRO_OPR_MODE_SUSPEND + * 0x04 | GYRO_OPR_MODE_ADVANCE_POWERSAVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_power_mode( +u8 *gyro_power_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro power mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Write the value of gyro power mode*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_POWER_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_power_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_POWER_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro power mode + * from page one register from 0x0B bit 0 to 2 + * + * @param gyro_power_mode_u8 : The value of gyro power mode + * + * gyro_power_mode_u8 | result + * ----------------------|---------------------------- + * 0x00 | GYRO_OPR_MODE_NORMAL + * 0x01 | GYRO_OPR_MODE_FASTPOWERUP + * 0x02 | GYRO_OPR_MODE_DEEPSUSPEND + * 0x03 | GYRO_OPR_MODE_SUSPEND + * 0x04 | GYRO_OPR_MODE_ADVANCE_POWERSAVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_power_mode( +u8 gyro_power_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 gyro_auto_sleep_durn = BNO055_INIT_VALUE; +u8 gyro_bw_u8 = BNO055_INIT_VALUE; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of power mode*/ + if ((gyro_power_mode_u8 == BNO055_INIT_VALUE || + gyro_power_mode_u8 > BNO055_INIT_VALUE) && + gyro_power_mode_u8 < BNO055_GYRO_RANGE) { + switch (gyro_power_mode_u8) { + case BNO055_GYRO_POWER_MODE_NORMAL: + gyro_power_mode_u8 = + BNO055_GYRO_POWER_MODE_NORMAL; + break; + case BNO055_GYRO_POWER_MODE_FASTPOWERUP: + gyro_power_mode_u8 = + BNO055_GYRO_POWER_MODE_FASTPOWERUP; + break; + case BNO055_GYRO_POWER_MODE_DEEPSUSPEND: + gyro_power_mode_u8 = + BNO055_GYRO_POWER_MODE_DEEPSUSPEND; + break; + case BNO055_GYRO_POWER_MODE_SUSPEND: + gyro_power_mode_u8 = + BNO055_GYRO_POWER_MODE_SUSPEND; + break; + case BNO055_GYRO_POWER_MODE_ADVANCE_POWERSAVE: + com_rslt = bno055_get_gyro_bw + (&gyro_bw_u8); + com_rslt += bno055_get_gyro_auto_sleep_durn + (&gyro_auto_sleep_durn); + if (com_rslt == BNO055_SUCCESS) + bno055_gyro_set_auto_sleep_durn + (gyro_auto_sleep_durn, + gyro_bw_u8); + com_rslt += + bno055_write_page_id(BNO055_PAGE_ONE); + gyro_power_mode_u8 = + BNO055_GYRO_POWER_MODE_ADVANCE_POWERSAVE; + break; + default: + break; + } + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_POWER_MODE, + gyro_power_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_POWER_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { + com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel sleep mode + * from page one register from 0x0C bit 0 + * + * @param sleep_tmr_u8 : The value of accel sleep mode + * + * sleep_tmr_u8 | result + * ----------------- |------------------------------------ + * 0x00 | enable EventDrivenSampling(EDT) + * 0x01 | enable Equidistant sampling mode(EST) + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_sleep_tmr_mode( +u8 *sleep_tmr_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel sleep mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* read the value of accel sleep mode */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_MODE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sleep_tmr_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_SLEEP_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel sleep mode + * from page one register from 0x0C bit 0 + * + * @param sleep_tmr_u8 : The value of accel sleep mode + * + * sleep_tmr_u8 | result + * ----------------- |------------------------------------ + * 0x00 | enable EventDrivenSampling(EDT) + * 0x01 | enable Equidistant sampling mode(EST) + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_sleep_tmr_mode( +u8 sleep_tmr_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (sleep_tmr_u8 < + BNO055_ACCEL_SLEEP_MODE_RANGE) { + /*Write the value + of accel sleep mode*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_SLEEP_MODE, + sleep_tmr_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel sleep duration + * from page one register from 0x0C bit 1 to 4 + * + * @param sleep_durn_u8 : The value of accel sleep duration + * + * sleep_durn_u8 | result + * ---------------- |----------------------------- + * 0x05 | BNO055_ACCEL_SLEEP_DURN_0_5MS + * 0x06 | BNO055_ACCEL_SLEEP_DURN_1MS + * 0x07 | BNO055_ACCEL_SLEEP_DURN_2MS + * 0x08 | BNO055_ACCEL_SLEEP_DURN_4MS + * 0x09 | BNO055_ACCEL_SLEEP_DURN_6MS + * 0x0A | BNO055_ACCEL_SLEEP_DURN_10MS + * 0x0B | BNO055_ACCEL_SLEEP_DURN_25MS + * 0x0C | BNO055_ACCEL_SLEEP_DURN_50MS + * 0x0D | BNO055_ACCEL_SLEEP_DURN_100MS + * 0x0E | BNO055_ACCEL_SLEEP_DURN_500MS + * 0x0F | BNO055_ACCEL_SLEEP_DURN_1S + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_sleep_durn( +u8 *sleep_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel sleep duration + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel sleep duration */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sleep_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_SLEEP_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel sleep duration + * from page one register from 0x0C bit 1 to 4 + * + * @param sleep_durn_u8 : The value of accel sleep duration + * + * sleep_durn_u8 | result + * ---------------|----------------------------- + * 0x05 | BNO055_ACCEL_SLEEP_DURN_0_5MS + * 0x06 | BNO055_ACCEL_SLEEP_DURN_1MS + * 0x07 | BNO055_ACCEL_SLEEP_DURN_2MS + * 0x08 | BNO055_ACCEL_SLEEP_DURN_4MS + * 0x09 | BNO055_ACCEL_SLEEP_DURN_6MS + * 0x0A | BNO055_ACCEL_SLEEP_DURN_10MS + * 0x0B | BNO055_ACCEL_SLEEP_DURN_25MS + * 0x0C | BNO055_ACCEL_SLEEP_DURN_50MS + * 0x0D | BNO055_ACCEL_SLEEP_DURN_100MS + * 0x0E | BNO055_ACCEL_SLEEP_DURN_500MS + * 0x0F | BNO055_ACCEL_SLEEP_DURN_1S + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_sleep_durn( +u8 sleep_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (sleep_durn_u8 < + BNO055_ACCEL_SLEEP_DURATION_RANGE) { + /* Write the accel + sleep duration*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_SLEEP_DURN, + sleep_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to write the gyro sleep duration + * from page one register from 0x0D bit 0 to 2 + * + * @param sleep_durn_u8 : The value of gyro sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_sleep_durn(u8 *sleep_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the gyro sleep duration */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLEEP_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sleep_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_SLEEP_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro sleep duration + * from page one register from 0x0D bit 0 to 2 + * + * @param sleep_durn_u8 : The value of gyro sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_sleep_durn(u8 sleep_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + if (sleep_durn_u8 < + BNO055_GYRO_AUTO_SLEEP_DURATION_RANGE) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the gyro + sleep duration */ + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_SLEEP_DURN, + sleep_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro auto sleep duration + * from page one register from 0x0D bit 3 to 5 + * + * @param auto_sleep_durn_u8 : The value of gyro auto sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_auto_sleep_durn( +u8 *auto_sleep_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro auto sleep duration */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AUTO_SLEEP_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *auto_sleep_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_AUTO_SLEEP_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro auto sleep duration + * from page one register from 0x0D bit 3 to 5 + * + * @param auto_sleep_durn_u8 : The value of gyro auto sleep duration + * @param bw : The value of gyro bandwidth + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_gyro_set_auto_sleep_durn( +u8 auto_sleep_durn_u8, u8 bw) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 auto_sleep_durn_u8r; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of gyro sleep duration */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AUTO_SLEEP_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (auto_sleep_durn_u8 < + BNO055_GYRO_AUTO_SLEEP_DURATION_RANGE) { + switch (bw) { + case BNO055_GYRO_BW_523HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_4MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_4MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_230HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_4MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_4MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_116HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_4MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_4MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_47HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_5MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_5MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_23HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_10MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_10MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_12HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_20MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_20MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_64HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_10MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_10MS_AUTOSLPDUR; + break; + case BNO055_GYRO_BW_32HZ: + if (auto_sleep_durn_u8 > + BNO055_GYRO_20MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_20MS_AUTOSLPDUR; + break; + default: + if (auto_sleep_durn_u8 > + BNO055_GYRO_4MS_AUTOSLPDUR) + auto_sleep_durn_u8r = + auto_sleep_durn_u8; + else + auto_sleep_durn_u8r = + BNO055_GYRO_4MS_AUTOSLPDUR; + break; + } + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_AUTO_SLEEP_DURN, + auto_sleep_durn_u8r); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AUTO_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_OUT_OF_RANGE; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { +com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the mag sleep mode + * from page one register from 0x0E bit 0 + * + * @param sleep_mode_u8 : The value of mag sleep mode + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_sleep_mode( +u8 *sleep_mode_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page,mag sleep mode is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of mag sleep mode*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *sleep_mode_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_SLEEP_MODE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the mag sleep mode + * from page one register from 0x0E bit 0 + * + * @param sleep_mode_u8 : The value of mag sleep mode + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_sleep_mode( +u8 sleep_mode_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value + of mag sleep mode*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_MAG_SLEEP_MODE, + sleep_mode_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_MODE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the mag sleep duration + * from page one register from 0x0E bit 1 to 4 + * + * @param sleep_durn_u8 : The value of mag sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_sleep_durn( +u8 *sleep_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page,mag sleep duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of mag sleep duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *sleep_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_MAG_SLEEP_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the mag sleep duration + * from page one register from 0x0E bit 1 to 4 + * + * @param sleep_durn_u8 : The value of mag sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_sleep_durn( +u8 sleep_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + mag sleep duration */ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_MAG_SLEEP_DURN, + sleep_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_MAG_SLEEP_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the gyro anymotion interrupt mask + * from page one register from 0x0F bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt mask + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_gyro_any_motion( +u8 *gyro_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro anymotion interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_INTR_MASK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro anymotion interrupt mask + * from page one register from 0x0F bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt mask + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_gyro_any_motion( +u8 gyro_any_motion_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Write the value of gyro anymotion interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_INTR_MASK, + gyro_any_motion_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the gyro highrate interrupt mask + * from page one register from 0x0F bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt mask + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following API + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_gyro_highrate( +u8 *gyro_highrate_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_INTR_MASK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro highrate interrupt mask + * from page one register from 0x0F bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt mask + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_gyro_highrate( +u8 gyro_highrate_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of gyro + highrate interrupt mask*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_INTR_MASK, + gyro_highrate_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel highg interrupt mask + * from page one register from 0x0F bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt mask + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_high_g( +u8 *accel_high_g_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel highg interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_high_g_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_INTR_MASK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel highg interrupt mask + * from page one register from 0x0F bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt mask + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_high_g( +u8 accel_high_g_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of accel + highg interrupt mask*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_INTR_MASK, + accel_high_g_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel anymotion interrupt mask + * from page one register from 0x0F bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt mask + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_any_motion( +u8 *accel_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* The value of accel anymotion interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_INTR_MASK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel anymotion interrupt mask + * from page one register from 0x0F bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt mask + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_any_motion( +u8 accel_any_motion_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Write the value of accel anymotion interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_INTR_MASK, + accel_any_motion_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel nomotion interrupt mask + * from page one register from 0x0F bit 7 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt mask + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres()) + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_no_motion( +u8 *accel_nomotion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel nomotion interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel nomotion interrupt mask*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_nomotion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_NO_MOTION_INTR_MASK); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel nomotion interrupt mask + * from page one register from 0x0F bit 7 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt mask + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_no_motion( +u8 accel_nomotion_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel + nomotion interrupt mask is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of accel + nomotion interrupt mask*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_NO_MOTION_INTR_MASK, + accel_nomotion_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_MASK_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the gyro anymotion interrupt + * from page one register from 0x10 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_gyro_any_motion( +u8 *gyro_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro anymotion interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_INTR); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro anymotion interrupt + * from page one register from 0x10 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_gyro_any_motion( +u8 gyro_any_motion_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Write the value of gyro anymotion interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_INTR, + gyro_any_motion_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the gyro highrate interrupt + * from page one register from 0x10 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_gyro_highrate( +u8 *gyro_highrate_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_INTR); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro highrate interrupt + * from page one register from 0x10 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_gyro_highrate( +u8 gyro_highrate_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of gyro highrate interrupt */ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_INTR, gyro_highrate_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel highg interrupt + * from page one register from 0x10 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_high_g( +u8 *accel_high_g_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel highg interrupt*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_high_g_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_INTR); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel highg interrupt + * from page one register from 0x10 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_high_g( +u8 accel_high_g_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of accel highg interrupt*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_INTR, + accel_high_g_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel anymotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_any_motion( +u8 *accel_any_motion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel anymotion interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_any_motion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_INTR); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel anymotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_any_motion( +u8 accel_any_motion_u8) +{ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel range is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Write the value of accel anymotion interrupt */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_INTR, + accel_any_motion_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel nomotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_no_motion( +u8 *accel_nomotion_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel nomotion interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel nomotion interrupt*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_nomotion_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_NO_MOTION_INTR); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel nomotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_no_motion( +u8 accel_nomotion_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, + accel nomotion interrupt is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + accel nomotion interrupt */ + data_u8r = BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_NO_MOTION_INTR, + accel_nomotion_u8); + com_rslt += p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_NO_MOTION_INTR_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to read the accel any motion threshold + * from page one register from 0x11 bit 0 to 7 + * + * @param accel_any_motion_thres_u8 : The value of any motion threshold + * accel_any_motion_thres_u8 | result + * ------------------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion threshold dependent on the + * range values + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_thres( +u8 *accel_any_motion_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel any motion threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel any motion threshold */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *accel_any_motion_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel any motion threshold + * from page one register from 0x11 bit 0 to 7 + * + * @param accel_any_motion_thres_u8 : The value of any motion threshold + * accel_any_motion_thres_u8 | result + * ------------------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion threshold dependent on the + * range values + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_thres( +u8 accel_any_motion_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + accel any motion threshold*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_THRES, + accel_any_motion_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel anymotion duration + * from page one register from 0x12 bit 0 to 1 + * + * @param accel_any_motion_durn_u8 : The value of accel anymotion duration + * accel_any_motion_durn_u8 | result + * ------------------------- | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_durn( +u8 *accel_any_motion_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel anymotion duration */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_DURN_SET_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_any_motion_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_DURN_SET); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel anymotion duration + * from page one register from 0x12 bit 0 to 1 + * + * @param accel_any_motion_durn_u8 : The value of accel anymotion duration + * + * accel_any_motion_durn_u8 | result + * ------------------------- | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_durn( +u8 accel_any_motion_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_DURN_SET_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + accel anymotion duration*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_DURN_SET, + accel_any_motion_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_DURN_SET_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel anymotion enable + * from page one register from 0x12 bit 2 to 4 + * + * @param data_u8 : The value of accel anymotion enable + * data_u8 | result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel anymotion axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS | 0 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 1 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_no_motion_axis_enable( +u8 channel_u8, u8 *data_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel anymotion enable is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + switch (channel_u8) { + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS: + /* Read the value of accel anymotion x enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_X_AXIS); + break; + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS: + /* Read the value of accel anymotion y enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_Y_AXIS); + break; + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_Z_AXIS: + /* Read the value of accel anymotion z enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_ANY_MOTION_Z_AXIS); + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel anymotion enable + * from page one register from 0x12 bit 2 to 4 + * + * @param data_u8 : The value of accel anymotion enable + * data_u8 | result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel anymotion axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS | 0 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 1 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_no_motion_axis_enable( +u8 channel_u8, u8 data_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + switch (channel_u8) { + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS: + /* Write the value of + accel anymotion x enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_ANY_MOTION_X_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_X_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS: + /* Write the value of + accel anymotion y enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_ANY_MOTION_Y_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Y_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_ACCEL_ANY_MOTION_NO_MOTION_Z_AXIS: + /* Write the value of + accel anymotion z enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_ACCEL_ANY_MOTION_Z_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_ANY_MOTION_Z_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel highg enable + * from page one register from 0x12 bit 5 to 7 + * + * @param data_u8 : The value of accel highg enable + * data_u8| result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel highg axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_HIGH_G_X_AXIS | 0 + * BNO055_ACCEL_HIGH_G_Y_AXIS | 1 + * BNO055_ACCEL_HIGH_G_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_axis_enable( +u8 channel_u8, u8 *data_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg enable is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + switch (channel_u8) { + case BNO055_ACCEL_HIGH_G_X_AXIS: + /* Read the value of accel x highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_X_AXIS); + break; + case BNO055_ACCEL_HIGH_G_Y_AXIS: + /* Read the value of accel y highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_Y_AXIS); + break; + case BNO055_ACCEL_HIGH_G_Z_AXIS: + /* Read the value of accel z highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_Z_AXIS); + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel highg enable + * from page one register from 0x12 bit 5 to 7 + * + * @param data_u8 : The value of accel highg enable + * data_u8| result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel highg axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_HIGH_G_X_AXIS | 0 + * BNO055_ACCEL_HIGH_G_Y_AXIS | 1 + * BNO055_ACCEL_HIGH_G_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_axis_enable( +u8 channel_u8, u8 data_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + switch (channel_u8) { + case BNO055_ACCEL_HIGH_G_X_AXIS: + /* Write the value of + accel x highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_X_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_X_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_X_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_ACCEL_HIGH_G_Y_AXIS: + /* Write the value of + accel y highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_Y_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Y_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_ACCEL_HIGH_G_Z_AXIS: + /* Write the value of + accel z highg enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_Z_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_Z_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the accel highg duration + * from page one register from 0x13 bit 0 to 7 + * + * @param accel_high_g_durn_u8 : The value of accel highg duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The high-g interrupt trigger delay according + * to [highg duration + 1] * 2 ms + * + * in a range from 2 ms to 512 ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_durn( +u8 *accel_high_g_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel highg duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel highg duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_high_g_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel highg duration + * from page one register from 0x13 bit 0 to 7 + * + * @param accel_high_g_durn_u8 : The value of accel highg duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The high-g interrupt trigger delay according + * to [highg duration + 1] * 2 ms + * + * in a range from 2 ms to 512 ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_durn( +u8 accel_high_g_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + accel highg duration*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_DURN, + accel_high_g_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the accel highg threshold + * from page one register from 0x14 bit 0 to 7 + * + * @param accel_high_g_thres_u8 : The value of accel highg threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 7.81mg | 1LSB + * 4g | 15.63mg | 1LSB + * 8g | 31.25mg | 1LSB + * 16g | 62.5mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_thres( +u8 *accel_high_g_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, highg threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of highg threshold */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_high_g_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel highg threshold + * from page one register from 0x14 bit 0 to 7 + * + * @param accel_high_g_thres_u8 : The value of accel highg threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 7.81mg | 1LSB + * 4g | 15.63mg | 1LSB + * 8g | 31.25mg | 1LSB + * 16g | 62.5mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_thres( +u8 accel_high_g_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Write the value of + accel highg threshold */ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_HIGH_G_THRES, + accel_high_g_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_HIGH_G_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read the accel slownomotion threshold + * from page one register from 0x15 bit 0 to 7 + * + * @param accel_slow_no_motion_thres_u8 : + * The value of accel slownomotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel slow no motion interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_thres( +u8 *accel_slow_no_motion_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel slownomotion threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of slownomotion threshold */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_slow_no_motion_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the accel slownomotion threshold + * from page one register from 0x15 bit 0 to 7 + * + * @param accel_slow_no_motion_thres_u8 : + * The value of accel slownomotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel slow no motion interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_thres( +u8 accel_slow_no_motion_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + slownomotion threshold */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_THRES, + accel_slow_no_motion_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read accel slownomotion enable + * from page one register from 0x16 bit 0 + * + * @param accel_slow_no_motion_en_u8 : The value of accel slownomotion enable + * accel_slow_no_motion_en_u8 | result + * ------------------------ | -------- + * 0x01 | Slow motion + * 0x00 | No motion + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_enable( +u8 *accel_slow_no_motion_en_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel slownomotion enable is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of accel slownomotion enable */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_ENABLE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_slow_no_motion_en_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_ENABLE); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write accel slownomotion enable + * from page one register from 0x16 bit 0 + * + * @param accel_slow_no_motion_en_u8 : The value of accel slownomotion enable + * accel_slow_no_motion_en_u8 | result + * ------------------------ | -------- + * 0x01 | Slow motion + * 0x00 | No motion + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_enable( +u8 accel_slow_no_motion_en_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_ENABLE_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /* Read the value of + accel slownomotion enable */ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_ENABLE, + accel_slow_no_motion_en_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_ENABLE_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read accel slownomotion duration + * from page one register from 0x16 bit 1 to 6 + * + * @param accel_slow_no_motion_durn_u8 : + * The value of accel slownomotion duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_durn( +u8 *accel_slow_no_motion_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, accel slownomotion duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /*read value of accel slownomotion duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *accel_slow_no_motion_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write accel slownomotion duration + * from page one register from 0x16 bit 1 to 6 + * + * @param accel_slow_no_motion_durn_u8 : + * The value of accel slownomotion duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_durn( +u8 accel_slow_no_motion_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + /*Write the value of accel + slownomotion duration*/ + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_ACCEL_SLOW_NO_MOTION_DURN, + accel_slow_no_motion_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_ACCEL_SLOW_NO_MOTION_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro anymotion enable + * from page one register from 0x17 bit 0 to 2 + * + * @param data_u8 : The value of gyro anymotion enable + * data_u8 | result + * ----------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro anymotion axis selection + * channel_u8 | value + * --------------------------- | ---------- + * BNO055_GYRO_ANY_MOTIONX_AXIS | 0 + * BNO055_GYRO_ANY_MOTIONY_AXIS | 1 + * BNO055_GYRO_ANY_MOTIONZ_AXIS | 2 + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_axis_enable( +u8 channel_u8, u8 *data_u8) +{ +/* Variable used to return value of +communication routine*/ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion axis is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + switch (channel_u8) { + case BNO055_GYRO_ANY_MOTION_X_AXIS: + /* Read the gyro anymotion x enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_X_AXIS); + break; + case BNO055_GYRO_ANY_MOTION_Y_AXIS: + /* Read the gyro anymotion y enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_Y_AXIS); + break; + case BNO055_GYRO_ANY_MOTION_Z_AXIS: + /* Read the gyro anymotion z enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_Z_AXIS); + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } +} +return com_rslt; +} +/*! + * @brief This API used to write the gyro anymotion enable + * from page one register from 0x17 bit 0 to 2 + * + * @param data_u8 : The value of gyro anymotion enable + * data_u8 | result + * ----------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro anymotion axis selection + * channel_u8 | value + * --------------------------- | ---------- + * BNO055_GYRO_ANY_MOTIONX_AXIS | 0 + * BNO055_GYRO_ANY_MOTIONY_AXIS | 1 + * BNO055_GYRO_ANY_MOTIONZ_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_axis_enable( +u8 channel_u8, u8 data_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + switch (channel_u8) { + case BNO055_GYRO_ANY_MOTION_X_AXIS: + /* Write the gyro + anymotion x enable*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_ANY_MOTION_X_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_GYRO_ANY_MOTION_Y_AXIS: + /* Write the gyro + anymotion y enable*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_ANY_MOTION_Y_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_GYRO_ANY_MOTION_Z_AXIS: + /* Write the gyro + anymotion z enable*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_ANY_MOTION_Z_AXIS, + data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + } + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} else { +com_rslt = BNO055_ERROR; +} +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read the gyro highrate enable + * from page one register from 0x17 bit 3 to 5 + * + * @param data_u8 : The value of gyro highrate enable + * data_u8 | result + * ---------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro highrate axis selection + * channel_u8 | value + * ------------------------ | ---------- + * BNO055_GYRO_HIGHRATE_X_AXIS | 0 + * BNO055_GYRO_HIGHRATE_Y_AXIS | 1 + * BNO055_GYRO_HIGHRATE_Z_AXIS | 2 + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_axis_enable( +u8 channel_u8, u8 *data_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate enable is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + switch (channel_u8) { + case BNO055_GYRO_HIGHRATE_X_AXIS: + /* Read the gyro highrate x enable */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_AXIS); + break; + case BNO055_GYRO_HIGHRATE_Y_AXIS: + /* Read the gyro highrate y enable */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_AXIS); + break; + case BNO055_GYRO_HIGHRATE_Z_AXIS: + /* Read the gyro highrate z enable */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *data_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_AXIS); + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write the gyro highrate enable + * from page one register from 0x17 bit 3 to 5 + * + * @param data_u8 : The value of gyro highrate enable + * data_u8 | result + * ---------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro highrate axis selection + * channel_u8 | value + * ------------------------ | ---------- + * BNO055_GYRO_HIGHRATE_X_AXIS | 0 + * BNO055_GYRO_HIGHRATE_Y_AXIS | 1 + * BNO055_GYRO_HIGHRATE_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_axis_enable( +u8 channel_u8, u8 data_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + switch (channel_u8) { + case BNO055_GYRO_HIGHRATE_X_AXIS: + /* Write the value of + gyro highrate x enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_HIGHRATE_X_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_GYRO_HIGHRATE_Y_AXIS: + /* Write the value of + gyro highrate y enable*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE( + data_u8r, + BNO055_GYRO_HIGHRATE_Y_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + case BNO055_GYRO_HIGHRATE_Z_AXIS: + /* Write the value of + gyro highrate z enable*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_AXIS_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = BNO055_SET_BITSLICE + (data_u8r, + BNO055_GYRO_HIGHRATE_Z_AXIS, data_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_AXIS_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + break; + default: + com_rslt = BNO055_OUT_OF_RANGE; + break; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro anymotion filter + * from page one register from 0x17 bit 6 + * + * @param gyro_any_motion_filter_u8 : The value of gyro anymotion filter + * gyro_any_motion_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_filter( +u8 *gyro_any_motion_filter_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion filter is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro anymotion filter*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_FILTER_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_filter_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_FILTER); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro anymotion filter + * from page one register from 0x17 bit 6 + * + * @param gyro_any_motion_filter_u8 : The value of gyro anymotion filter + * gyro_any_motion_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_filter( +u8 gyro_any_motion_filter_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro anymotion filter*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_FILTER_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_FILTER, + gyro_any_motion_filter_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_FILTER_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate filter + * from page one register from 0x17 bit 7 + * + * @param gyro_highrate_filter_u8 : The value of gyro highrate filter + * gyro_highrate_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_filter( +u8 *gyro_highrate_filter_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate filter is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate filter */ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_FILTER_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_filter_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_FILTER); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate filter + * from page one register from 0x17 bit 7 + * + * @param gyro_highrate_filter_u8 : The value of gyro highrate filter + * gyro_highrate_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_filter( +u8 gyro_highrate_filter_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro highrate filter*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_FILTER_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_FILTER, + gyro_highrate_filter_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_FILTER_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate x threshold + * from page one register from 0x18 bit 0 to 4 + * + * @param gyro_highrate_x_thres_u8 : The value of gyro x highrate threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_thres( +u8 *gyro_highrate_x_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate x threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_x_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate x threshold + * from page one register from 0x18 bit 0 to 4 + * + * @param gyro_highrate_x_thres_u8 : The value of gyro x highrate threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_thres( +u8 gyro_highrate_x_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro highrate x threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_THRES, + gyro_highrate_x_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate x hysteresis + * from page one register from 0x18 bit 5 to 6 + * + * @param gyro_highrate_x_hyst_u8 : The value of gyro highrate x hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_x_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_hyst( +u8 *gyro_highrate_x_hyst_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page,gyro highrate x hysteresis is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate x hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_HYST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_x_hyst_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_HYST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate x hysteresis + * from page one register from 0x18 bit 5 to 6 + * + * @param gyro_highrate_x_hyst_u8 : The value of gyro highrate x hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_x_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_hyst( +u8 gyro_highrate_x_hyst_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /*Write the value of + gyro highrate x hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_HYST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_HYST, + gyro_highrate_x_hyst_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_HYST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate x duration + * from page one register from 0x19 bit 0 to 7 + * + * @param gyro_highrate_x_durn_u8 : The value of gyro highrate x duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_x_durn_u8)*2.5ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_durn( +u8 *gyro_highrate_x_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate x duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate x duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_x_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate x duration + * from page one register from 0x19 bit 0 to 7 + * + * @param gyro_highrate_x_durn_u8 : The value of gyro highrate x duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_x_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_durn( +u8 gyro_highrate_x_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro highrate x duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_X_DURN, + gyro_highrate_x_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_X_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read gyro highrate y threshold + * from page one register from 0x1A bit 0 to 4 + * + * @param gyro_highrate_y_thres_u8 : The value of gyro highrate y threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_thres( +u8 *gyro_highrate_y_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate y threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate y threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_y_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate y threshold + * from page one register from 0x1A bit 0 to 4 + * + * @param gyro_highrate_y_thres_u8 : The value of gyro highrate y threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_thres( +u8 gyro_highrate_y_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro highrate y threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_THRES, + gyro_highrate_y_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate y hysteresis + * from page one register from 0x1A bit 5 to 6 + * + * @param gyro_highrate_y_hyst_u8 : The value of gyro highrate y hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_y_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_hyst( +u8 *gyro_highrate_y_hyst_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate y hysteresis is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate y hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_HYST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_y_hyst_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_HYST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate y hysteresis + * from page one register from 0x1A bit 5 to 6 + * + * @param gyro_highrate_y_hyst_u8 : The value of gyro highrate y hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_y_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_hyst( +u8 gyro_highrate_y_hyst_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro highrate y hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_HYST_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_HYST, + gyro_highrate_y_hyst_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_HYST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate y duration + * from page one register from 0x1B bit 0 to 7 + * + * @param gyro_highrate_y_durn_u8 : The value of gyro highrate y duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_y_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_durn( +u8 *gyro_highrate_y_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate y duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate y duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_y_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate y duration + * from page one register from 0x1B bit 0 to 7 + * + * @param gyro_highrate_y_durn_u8 : The value of gyro highrate y duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_y_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_durn( +u8 gyro_highrate_y_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro highrate y duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Y_DURN, + gyro_highrate_y_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Y_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read gyro highrate z threshold + * from page one register from 0x1C bit 0 to 4 + * + * @param gyro_highrate_z_thres_u8 : The value of gyro highrate z threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_thres( +u8 *gyro_highrate_z_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate z threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate z threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_z_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate z threshold + * from page one register from 0x1C bit 0 to 4 + * + * @param gyro_highrate_z_thres_u8 : The value of gyro highrate z threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_thres( +u8 gyro_highrate_z_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro highrate z threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_THRES, + gyro_highrate_z_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate z hysteresis + * from page one register from 0x1C bit 5 to 6 + * + * @param gyro_highrate_z_hyst_u8 : The value of gyro highrate z hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_z_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_hyst( +u8 *gyro_highrate_z_hyst_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate z hysteresis is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate z hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_HYST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_z_hyst_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_HYST); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate z hysteresis + * from page one register from 0x1C bit 5 to 6 + * + * @param gyro_highrate_z_hyst_u8 : The value of gyro highrate z hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_z_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_hyst( +u8 gyro_highrate_z_hyst_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro highrate z hysteresis*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_HYST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_HYST, + gyro_highrate_z_hyst_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_HYST_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro highrate z duration + * from page one register from 0x1D bit 0 to 7 + * + * @param gyro_highrate_z_durn_u8 : The value of gyro highrate z duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_z_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_durn( +u8 *gyro_highrate_z_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro highrate z duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro highrate z duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_highrate_z_durn_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro highrate z duration + * from page one register from 0x1D bit 0 to 7 + * + * @param gyro_highrate_z_durn_u8 : The value of gyro highrate z duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_z_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_durn( +u8 gyro_highrate_z_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro highrate z duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_HIGHRATE_Z_DURN, + gyro_highrate_z_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_HIGHRATE_Z_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read gyro anymotion threshold + * from page one register from 0x1E bit 0 to 6 + * + * @param gyro_any_motion_thres_u8 : The value of gyro anymotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt threshold dependent + * on the selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 1dps | 1LSB + * 1000 | 0.5dps | 1LSB + * 500 | 0.25dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_thres( +u8 *gyro_any_motion_thres_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page,gyro anymotion threshold is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro anymotion threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_THRES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_thres_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_THRES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro anymotion threshold + * from page one register from 0x1E bit 0 to 6 + * + * @param gyro_any_motion_thres_u8 : The value of gyro anymotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt threshold dependent + * on the selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 1dps | 1LSB + * 1000 | 0.5dps | 1LSB + * 500 | 0.25dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_thres( +u8 gyro_any_motion_thres_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +s8 pg_stat_s8 = BNO055_ERROR; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value + of gyro anymotion threshold*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_ANY_MOTION_THRES, + gyro_any_motion_thres_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_ANY_MOTION_THRES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } +} +if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); +return com_rslt; +} +/*! + * @brief This API used to read gyro anymotion slope samples + * from page one register from 0x1F bit 0 to 1 + * + * @param gyro_any_motion_slope_samples_u8 : + * The value of gyro anymotion slope samples + * gyro_any_motion_slope_samples_u8 | result + * ---------------------------------- | ----------- + * 0 | 8 samples + * 1 | 16 samples + * 2 | 32 samples + * 3 | 64 samples + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_slope_samples( +u8 *gyro_any_motion_slope_samples_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion slope samples is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /*Read the value of gyro anymotion slope samples*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLOPE_SAMPLES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_any_motion_slope_samples_u8 = + BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_SLOPE_SAMPLES); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro anymotion slope samples + * from page one register from 0x1F bit 0 to 1 + * + * @param gyro_any_motion_slope_samples_u8 : + * The value of gyro anymotion slope samples + * gyro_any_motion_slope_samples_u8 | result + * ---------------------------------- | ----------- + * 0 | 8 samples + * 1 | 16 samples + * 2 | 32 samples + * 3 | 64 samples + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_slope_samples( +u8 gyro_any_motion_slope_samples_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; +} else { +/* The write operation effective only if the operation +mode is in config mode, this part of code is checking the +current operation mode and set the config mode */ +stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); +if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of + gyro anymotion slope samples*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLOPE_SAMPLES_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_SLOPE_SAMPLES, + gyro_any_motion_slope_samples_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_SLOPE_SAMPLES_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode of + previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} +/*! + * @brief This API used to read gyro anymotion awake duration + * from page one register from 0x1F bit 2 to 3 + * + * @param gyro_awake_durn_u8 : The value of gyro anymotion awake duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_awake_durn( +u8 *gyro_awake_durn_u8) +{ + /* Variable used to return value of + communication routine*/ + BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; + u8 data_u8r = BNO055_INIT_VALUE; + s8 stat_s8 = BNO055_ERROR; + /* Check the struct p_bno055 is empty */ + if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /*condition check for page, gyro anymotion awake duration is + available in the page one*/ + if (p_bno055->page_id != BNO055_PAGE_ONE) + /* Write page as one */ + stat_s8 = bno055_write_page_id(BNO055_PAGE_ONE); + if ((stat_s8 == BNO055_SUCCESS) || + (p_bno055->page_id == BNO055_PAGE_ONE)) { + /* Read the value of gyro anymotion awake duration*/ + com_rslt = p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AWAKE_DURN_REG, + &data_u8r, BNO055_GEN_READ_WRITE_LENGTH); + *gyro_awake_durn_u8 = BNO055_GET_BITSLICE(data_u8r, + BNO055_GYRO_AWAKE_DURN); + } else { + com_rslt = BNO055_ERROR; + } + } + return com_rslt; +} +/*! + * @brief This API used to write gyro anymotion awake duration + * from page one register from 0x1F bit 2 to 3 + * + * @param gyro_awake_durn_u8 : The value of gyro anymotion awake duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_awake_durn( +u8 gyro_awake_durn_u8) +{ +BNO055_RETURN_FUNCTION_TYPE com_rslt = BNO055_ERROR; +u8 data_u8r = BNO055_INIT_VALUE; +s8 stat_s8 = BNO055_ERROR; +s8 pg_stat_s8 = BNO055_ERROR; +u8 prev_opmode_u8 = BNO055_OPERATION_MODE_CONFIG; +/* Check the struct p_bno055 is empty */ +if (p_bno055 == BNO055_INIT_VALUE) { + return BNO055_E_NULL_PTR; + } else { + /* The write operation effective only if the operation + mode is in config mode, this part of code is checking the + current operation mode and set the config mode */ + stat_s8 = bno055_get_operation_mode(&prev_opmode_u8); + if (stat_s8 == BNO055_SUCCESS) { + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + stat_s8 += bno055_set_operation_mode + (BNO055_OPERATION_MODE_CONFIG); + if (stat_s8 == BNO055_SUCCESS) { + /* Write page as one */ + pg_stat_s8 = bno055_write_page_id( + BNO055_PAGE_ONE); + if (pg_stat_s8 == BNO055_SUCCESS) { + /* Write the value of gyro + anymotion awake duration*/ + com_rslt = + p_bno055->BNO055_BUS_READ_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AWAKE_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + if (com_rslt == BNO055_SUCCESS) { + data_u8r = + BNO055_SET_BITSLICE(data_u8r, + BNO055_GYRO_AWAKE_DURN, + gyro_awake_durn_u8); + com_rslt += + p_bno055->BNO055_BUS_WRITE_FUNC + (p_bno055->dev_addr, + BNO055_GYRO_AWAKE_DURN_REG, + &data_u8r, + BNO055_GEN_READ_WRITE_LENGTH); + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } else { + com_rslt = BNO055_ERROR; + } + } + if (prev_opmode_u8 != BNO055_OPERATION_MODE_CONFIG) + /* set the operation mode + of previous operation mode*/ + com_rslt += bno055_set_operation_mode + (prev_opmode_u8); + return com_rslt; +} diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.h b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.h new file mode 100644 index 0000000000..e1abb3ac02 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055.h @@ -0,0 +1,7973 @@ +/** \mainpage +* +**************************************************************************** +* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH +* +* File : bno055.h +* +* Date : 2016/03/14 +* +* Revision : 2.0.3 $ +* +* Usage: Sensor Driver file for BNO055 sensor +* +**************************************************************************** +* \section License +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* Neither the name of the copyright holder nor the names of the +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND +* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR +* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER +* OR CONTRIBUTORS BE LIABLE FOR ANY +* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, +* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, +* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE +* +* The information provided is believed to be accurate and reliable. +* The copyright holder assumes no responsibility +* for the consequences of use +* of such information nor for any infringement of patents or +* other rights of third parties which may result from its use. +* No license is granted by implication or otherwise under any patent or +* patent rights of the copyright holder. +**************************************************************************/ +/*! \file bno055.h + \brief BNO055 Sensor Driver Support Header File */ + +#ifndef __BNO055_H__ +#define __BNO055_H__ +/****************************************************************/ +/**\name DATA TYPES INCLUDES */ +/************************************************************/ +/*! +* @brief The following definition uses for define the data types +* +* @note While porting the API please consider the following +* @note Please check the version of C standard +* @note Are you using Linux platform +*/ + +/*! +* @brief For the Linux platform support +* Please use the types.h for your data types definitions +*/ +#ifdef __KERNEL__ + +#include +/* singed integer type*/ +typedef int8_t s8;/**< used for signed 8bit */ +typedef int16_t s16;/**< used for signed 16bit */ +typedef int32_t s32;/**< used for signed 32bit */ +typedef int64_t s64;/**< used for signed 64bit */ + +typedef u_int8_t u8;/**< used for unsigned 8bit */ +typedef u_int16_t u16;/**< used for unsigned 16bit */ +typedef u_int32_t u32;/**< used for unsigned 32bit */ +typedef u_int64_t u64;/**< used for unsigned 64bit */ + + + +#else /* ! __KERNEL__ */ +/********************************************************** +* These definition uses for define the C +* standard version data types +***********************************************************/ +# if !defined(__STDC_VERSION__) + +/************************************************ + * compiler is C11 C standard +************************************************/ +#if (__STDC_VERSION__ == 201112L) + +/************************************************/ +#include +/************************************************/ + +/*unsigned integer types*/ +typedef uint8_t u8;/**< used for unsigned 8bit */ +typedef uint16_t u16;/**< used for unsigned 16bit */ +typedef uint32_t u32;/**< used for unsigned 32bit */ +typedef uint64_t u64;/**< used for unsigned 64bit */ + +/*signed integer types*/ +typedef int8_t s8;/**< used for signed 8bit */ +typedef int16_t s16;/**< used for signed 16bit */ +typedef int32_t s32;/**< used for signed 32bit */ +typedef int64_t s64;/**< used for signed 64bit */ +/************************************************ + * compiler is C99 C standard +************************************************/ + +#elif (__STDC_VERSION__ == 199901L) + +/* stdint.h is a C99 supported c library. +which is used to fixed the integer size*/ +/************************************************/ +#include +/************************************************/ + +/*unsigned integer types*/ +typedef uint8_t u8;/**< used for unsigned 8bit */ +typedef uint16_t u16;/**< used for unsigned 16bit */ +typedef uint32_t u32;/**< used for unsigned 32bit */ +typedef uint64_t u64;/**< used for unsigned 64bit */ + +/*signed integer types*/ +typedef int8_t s8;/**< used for signed 8bit */ +typedef int16_t s16;/**< used for signed 16bit */ +typedef int32_t s32;/**< used for signed 32bit */ +typedef int64_t s64;/**< used for signed 64bit */ +/************************************************ + * compiler is C89 or other C standard +************************************************/ + +#else /* !defined(__STDC_VERSION__) */ +/*! +* @brief By default it is defined as 32 bit machine configuration +* define your data types based on your +* machine/compiler/controller configuration +*/ +#define MACHINE_32_BIT + +/*! @brief + * If your machine support 16 bit + * define the MACHINE_16_BIT + */ +#ifdef MACHINE_16_BIT +#include +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed long int s32;/**< used for signed 32bit */ + +#if defined(LONG_MAX) && LONG_MAX == 0x7fffffffffffffffL +typedef long int s64;/**< used for signed 64bit */ +typedef unsigned long int u64;/**< used for unsigned 64bit */ +#elif defined(LLONG_MAX) && (LLONG_MAX == 0x7fffffffffffffffLL) +typedef long long int s64;/**< used for signed 64bit */ +typedef unsigned long long int u64;/**< used for unsigned 64bit */ +#else +#warning Either the correct data type for signed 64 bit integer \ +could not be found, or 64 bit integers are not supported in your environment. +#warning If 64 bit integers are supported on your platform, \ +please set s64 manually. +#endif + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned long int u32;/**< used for unsigned 32bit */ + +/* If your machine support 32 bit +define the MACHINE_32_BIT*/ +#elif defined MACHINE_32_BIT +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed int s32;/**< used for signed 32bit */ +typedef signed long long int s64;/**< used for signed 64bit */ + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned int u32;/**< used for unsigned 32bit */ +typedef unsigned long long int u64;/**< used for unsigned 64bit */ + +/* If your machine support 64 bit +define the MACHINE_64_BIT*/ +#elif defined MACHINE_64_BIT +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed int s32;/**< used for signed 32bit */ +typedef signed long int s64;/**< used for signed 64bit */ + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned int u32;/**< used for unsigned 32bit */ +typedef unsigned long int u64;/**< used for unsigned 64bit */ + +#else +#warning The data types defined above which not supported \ +define the data types manually +#endif +#endif + +/*** This else will execute for the compilers + * which are not supported the C standards + * Like C89/C99/C11***/ +#else +/*! +* @brief By default it is defined as 32 bit machine configuration +* define your data types based on your +* machine/compiler/controller configuration +*/ +#define MACHINE_32_BIT + +/* If your machine support 16 bit +define the MACHINE_16_BIT*/ +#ifdef MACHINE_16_BIT +#include +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed long int s32;/**< used for signed 32bit */ + +#if defined(LONG_MAX) && LONG_MAX == 0x7fffffffffffffffL +typedef long int s64;/**< used for signed 64bit */ +typedef unsigned long int u64;/**< used for unsigned 64bit */ +#elif defined(LLONG_MAX) && (LLONG_MAX == 0x7fffffffffffffffLL) +typedef long long int s64;/**< used for signed 64bit */ +typedef unsigned long long int u64;/**< used for unsigned 64bit */ +#else +#warning Either the correct data type for signed 64 bit integer \ +could not be found, or 64 bit integers are not supported in your environment. +#warning If 64 bit integers are supported on your platform, \ +please set s64 manually. +#endif + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned long int u32;/**< used for unsigned 32bit */ + +/*! @brief If your machine support 32 bit +define the MACHINE_32_BIT*/ +#elif defined MACHINE_32_BIT +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed int s32;/**< used for signed 32bit */ +typedef signed long long int s64;/**< used for signed 64bit */ + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned int u32;/**< used for unsigned 32bit */ +typedef unsigned long long int u64;/**< used for unsigned 64bit */ + +/* If your machine support 64 bit +define the MACHINE_64_BIT*/ +#elif defined MACHINE_64_BIT +/*signed integer types*/ +typedef signed char s8;/**< used for signed 8bit */ +typedef signed short int s16;/**< used for signed 16bit */ +typedef signed int s32;/**< used for signed 32bit */ +typedef signed long int s64;/**< used for signed 64bit */ + +/*unsigned integer types*/ +typedef unsigned char u8;/**< used for unsigned 8bit */ +typedef unsigned short int u16;/**< used for unsigned 16bit */ +typedef unsigned int u32;/**< used for unsigned 32bit */ +typedef unsigned long int u64;/**< used for unsigned 64bit */ + +#else +#warning The data types defined above which not supported \ +define the data types manually +#endif +#endif +#endif +/***************************************************************/ +/**\name BUS READ AND WRITE FUNCTIONS */ +/***************************************************************/ +#define BNO055_WR_FUNC_PTR s8 (*bus_write)\ +(u8, u8, u8 *, u8) + +#define BNO055_BUS_WRITE_FUNC(dev_addr, reg_addr, reg_data, wr_len)\ + bus_write(dev_addr, reg_addr, reg_data, wr_len) + +#define BNO055_RD_FUNC_PTR s8 \ +(*bus_read)(u8, u8, u8 *, u8) + +#define BNO055_BUS_READ_FUNC(dev_addr, reg_addr, reg_data, r_len)\ +bus_read(dev_addr, reg_addr, reg_data, r_len) + +#define BNO055_DELAY_RETURN_TYPE void + +#define BNO055_DELAY_PARAM_TYPES u32 + +#define BNO055_DELAY_FUNC(delay_in_msec)\ + delay_func(delay_in_msec) + +/********************************************************/ +/**\name I2C ADDRESS DEFINITION FOR BNO055 */ +/********************************************************/ +/* bno055 I2C Address */ +#define BNO055_I2C_ADDR1 (0x28) +#define BNO055_I2C_ADDR2 (0x29) + +/***************************************************/ +/**\name REGISTER ADDRESS DEFINITION */ +/***************************************************/ +/* Page id register definition*/ +#define BNO055_PAGE_ID_ADDR (0X07) + +/* PAGE0 REGISTER DEFINITION START*/ +#define BNO055_CHIP_ID_ADDR (0x00) +#define BNO055_ACCEL_REV_ID_ADDR (0x01) +#define BNO055_MAG_REV_ID_ADDR (0x02) +#define BNO055_GYRO_REV_ID_ADDR (0x03) +#define BNO055_SW_REV_ID_LSB_ADDR (0x04) +#define BNO055_SW_REV_ID_MSB_ADDR (0x05) +#define BNO055_BL_REV_ID_ADDR (0X06) + +/* Accel data register*/ +#define BNO055_ACCEL_DATA_X_LSB_ADDR (0X08) +#define BNO055_ACCEL_DATA_X_MSB_ADDR (0X09) +#define BNO055_ACCEL_DATA_Y_LSB_ADDR (0X0A) +#define BNO055_ACCEL_DATA_Y_MSB_ADDR (0X0B) +#define BNO055_ACCEL_DATA_Z_LSB_ADDR (0X0C) +#define BNO055_ACCEL_DATA_Z_MSB_ADDR (0X0D) + +/*Mag data register*/ +#define BNO055_MAG_DATA_X_LSB_ADDR (0X0E) +#define BNO055_MAG_DATA_X_MSB_ADDR (0X0F) +#define BNO055_MAG_DATA_Y_LSB_ADDR (0X10) +#define BNO055_MAG_DATA_Y_MSB_ADDR (0X11) +#define BNO055_MAG_DATA_Z_LSB_ADDR (0X12) +#define BNO055_MAG_DATA_Z_MSB_ADDR (0X13) + +/*Gyro data registers*/ +#define BNO055_GYRO_DATA_X_LSB_ADDR (0X14) +#define BNO055_GYRO_DATA_X_MSB_ADDR (0X15) +#define BNO055_GYRO_DATA_Y_LSB_ADDR (0X16) +#define BNO055_GYRO_DATA_Y_MSB_ADDR (0X17) +#define BNO055_GYRO_DATA_Z_LSB_ADDR (0X18) +#define BNO055_GYRO_DATA_Z_MSB_ADDR (0X19) + +/*Euler data registers*/ +#define BNO055_EULER_H_LSB_ADDR (0X1A) +#define BNO055_EULER_H_MSB_ADDR (0X1B) + +#define BNO055_EULER_R_LSB_ADDR (0X1C) +#define BNO055_EULER_R_MSB_ADDR (0X1D) + +#define BNO055_EULER_P_LSB_ADDR (0X1E) +#define BNO055_EULER_P_MSB_ADDR (0X1F) + +/*Quaternion data registers*/ +#define BNO055_QUATERNION_DATA_W_LSB_ADDR (0X20) +#define BNO055_QUATERNION_DATA_W_MSB_ADDR (0X21) +#define BNO055_QUATERNION_DATA_X_LSB_ADDR (0X22) +#define BNO055_QUATERNION_DATA_X_MSB_ADDR (0X23) +#define BNO055_QUATERNION_DATA_Y_LSB_ADDR (0X24) +#define BNO055_QUATERNION_DATA_Y_MSB_ADDR (0X25) +#define BNO055_QUATERNION_DATA_Z_LSB_ADDR (0X26) +#define BNO055_QUATERNION_DATA_Z_MSB_ADDR (0X27) + +/* Linear acceleration data registers*/ +#define BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR (0X28) +#define BNO055_LINEAR_ACCEL_DATA_X_MSB_ADDR (0X29) +#define BNO055_LINEAR_ACCEL_DATA_Y_LSB_ADDR (0X2A) +#define BNO055_LINEAR_ACCEL_DATA_Y_MSB_ADDR (0X2B) +#define BNO055_LINEAR_ACCEL_DATA_Z_LSB_ADDR (0X2C) +#define BNO055_LINEAR_ACCEL_DATA_Z_MSB_ADDR (0X2D) + +/*Gravity data registers*/ +#define BNO055_GRAVITY_DATA_X_LSB_ADDR (0X2E) +#define BNO055_GRAVITY_DATA_X_MSB_ADDR (0X2F) +#define BNO055_GRAVITY_DATA_Y_LSB_ADDR (0X30) +#define BNO055_GRAVITY_DATA_Y_MSB_ADDR (0X31) +#define BNO055_GRAVITY_DATA_Z_LSB_ADDR (0X32) +#define BNO055_GRAVITY_DATA_Z_MSB_ADDR (0X33) + +/* Temperature data register*/ +#define BNO055_TEMP_ADDR (0X34) + +/* Status registers*/ +#define BNO055_CALIB_STAT_ADDR (0X35) +#define BNO055_SELFTEST_RESULT_ADDR (0X36) +#define BNO055_INTR_STAT_ADDR (0X37) +#define BNO055_SYS_CLK_STAT_ADDR (0X38) +#define BNO055_SYS_STAT_ADDR (0X39) +#define BNO055_SYS_ERR_ADDR (0X3A) + +/* Unit selection register*/ +#define BNO055_UNIT_SEL_ADDR (0X3B) +#define BNO055_DATA_SELECT_ADDR (0X3C) + +/* Mode registers*/ +#define BNO055_OPR_MODE_ADDR (0X3D) +#define BNO055_PWR_MODE_ADDR (0X3E) + +#define BNO055_SYS_TRIGGER_ADDR (0X3F) +#define BNO055_TEMP_SOURCE_ADDR (0X40) +/* Axis remap registers*/ +#define BNO055_AXIS_MAP_CONFIG_ADDR (0X41) +#define BNO055_AXIS_MAP_SIGN_ADDR (0X42) + +/* SIC registers*/ +#define BNO055_SIC_MATRIX_0_LSB_ADDR (0X43) +#define BNO055_SIC_MATRIX_0_MSB_ADDR (0X44) +#define BNO055_SIC_MATRIX_1_LSB_ADDR (0X45) +#define BNO055_SIC_MATRIX_1_MSB_ADDR (0X46) +#define BNO055_SIC_MATRIX_2_LSB_ADDR (0X47) +#define BNO055_SIC_MATRIX_2_MSB_ADDR (0X48) +#define BNO055_SIC_MATRIX_3_LSB_ADDR (0X49) +#define BNO055_SIC_MATRIX_3_MSB_ADDR (0X4A) +#define BNO055_SIC_MATRIX_4_LSB_ADDR (0X4B) +#define BNO055_SIC_MATRIX_4_MSB_ADDR (0X4C) +#define BNO055_SIC_MATRIX_5_LSB_ADDR (0X4D) +#define BNO055_SIC_MATRIX_5_MSB_ADDR (0X4E) +#define BNO055_SIC_MATRIX_6_LSB_ADDR (0X4F) +#define BNO055_SIC_MATRIX_6_MSB_ADDR (0X50) +#define BNO055_SIC_MATRIX_7_LSB_ADDR (0X51) +#define BNO055_SIC_MATRIX_7_MSB_ADDR (0X52) +#define BNO055_SIC_MATRIX_8_LSB_ADDR (0X53) +#define BNO055_SIC_MATRIX_8_MSB_ADDR (0X54) + +/* Accelerometer Offset registers*/ +#define BNO055_ACCEL_OFFSET_X_LSB_ADDR (0X55) +#define BNO055_ACCEL_OFFSET_X_MSB_ADDR (0X56) +#define BNO055_ACCEL_OFFSET_Y_LSB_ADDR (0X57) +#define BNO055_ACCEL_OFFSET_Y_MSB_ADDR (0X58) +#define BNO055_ACCEL_OFFSET_Z_LSB_ADDR (0X59) +#define BNO055_ACCEL_OFFSET_Z_MSB_ADDR (0X5A) + +/* Magnetometer Offset registers*/ +#define BNO055_MAG_OFFSET_X_LSB_ADDR (0X5B) +#define BNO055_MAG_OFFSET_X_MSB_ADDR (0X5C) +#define BNO055_MAG_OFFSET_Y_LSB_ADDR (0X5D) +#define BNO055_MAG_OFFSET_Y_MSB_ADDR (0X5E) +#define BNO055_MAG_OFFSET_Z_LSB_ADDR (0X5F) +#define BNO055_MAG_OFFSET_Z_MSB_ADDR (0X60) + +/* Gyroscope Offset registers*/ +#define BNO055_GYRO_OFFSET_X_LSB_ADDR (0X61) +#define BNO055_GYRO_OFFSET_X_MSB_ADDR (0X62) +#define BNO055_GYRO_OFFSET_Y_LSB_ADDR (0X63) +#define BNO055_GYRO_OFFSET_Y_MSB_ADDR (0X64) +#define BNO055_GYRO_OFFSET_Z_LSB_ADDR (0X65) +#define BNO055_GYRO_OFFSET_Z_MSB_ADDR (0X66) + +/* Radius registers*/ +#define BNO055_ACCEL_RADIUS_LSB_ADDR (0X67) +#define BNO055_ACCEL_RADIUS_MSB_ADDR (0X68) +#define BNO055_MAG_RADIUS_LSB_ADDR (0X69) +#define BNO055_MAG_RADIUS_MSB_ADDR (0X6A) +/* PAGE0 REGISTERS DEFINITION END*/ + +/* PAGE1 REGISTERS DEFINITION START*/ +/* Configuration registers*/ +#define BNO055_ACCEL_CONFIG_ADDR (0X08) +#define BNO055_MAG_CONFIG_ADDR (0X09) +#define BNO055_GYRO_CONFIG_ADDR (0X0A) +#define BNO055_GYRO_MODE_CONFIG_ADDR (0X0B) +#define BNO055_ACCEL_SLEEP_CONFIG_ADDR (0X0C) +#define BNO055_GYRO_SLEEP_CONFIG_ADDR (0X0D) +#define BNO055_MAG_SLEEP_CONFIG_ADDR (0x0E) + +/* Interrupt registers*/ +#define BNO055_INT_MASK_ADDR (0X0F) +#define BNO055_INT_ADDR (0X10) +#define BNO055_ACCEL_ANY_MOTION_THRES_ADDR (0X11) +#define BNO055_ACCEL_INTR_SETTINGS_ADDR (0X12) +#define BNO055_ACCEL_HIGH_G_DURN_ADDR (0X13) +#define BNO055_ACCEL_HIGH_G_THRES_ADDR (0X14) +#define BNO055_ACCEL_NO_MOTION_THRES_ADDR (0X15) +#define BNO055_ACCEL_NO_MOTION_SET_ADDR (0X16) +#define BNO055_GYRO_INTR_SETING_ADDR (0X17) +#define BNO055_GYRO_HIGHRATE_X_SET_ADDR (0X18) +#define BNO055_GYRO_DURN_X_ADDR (0X19) +#define BNO055_GYRO_HIGHRATE_Y_SET_ADDR (0X1A) +#define BNO055_GYRO_DURN_Y_ADDR (0X1B) +#define BNO055_GYRO_HIGHRATE_Z_SET_ADDR (0X1C) +#define BNO055_GYRO_DURN_Z_ADDR (0X1D) +#define BNO055_GYRO_ANY_MOTION_THRES_ADDR (0X1E) +#define BNO055_GYRO_ANY_MOTION_SET_ADDR (0X1F) +/* PAGE1 REGISTERS DEFINITION END*/ + + +#define BNO055_MDELAY_DATA_TYPE u32 + +/*< This refers BNO055 return type as s8 */ +#define BNO055_RETURN_FUNCTION_TYPE s8 + +/* Compile switch definition for Float and double*/ +#define BNO055_FLOAT_ENABLE +#define BNO055_DOUBLE_ENABLE +/**************************************************************/ +/**\name STRUCTURE DEFINITIONS */ +/**************************************************************/ +/*! +* @brief bno055 struct +*/ +struct bno055_t { +u8 chip_id;/**< chip_id of bno055 */ +u16 sw_rev_id;/**< software revision id of bno055 */ +u8 page_id;/**< page_id of bno055 */ +u8 accel_rev_id;/**< accel revision id of bno055 */ +u8 mag_rev_id;/**< mag revision id of bno055 */ +u8 gyro_rev_id;/**< gyro revision id of bno055 */ +u8 bl_rev_id;/**< boot loader revision id of bno055 */ +u8 dev_addr;/**< i2c device address of bno055 */ +BNO055_WR_FUNC_PTR;/**< bus write function pointer */ +BNO055_RD_FUNC_PTR;/**> bitname##_POS) + + +#define BNO055_SET_BITSLICE(regvar, bitname, val)\ +((regvar & ~bitname##_MSK) | ((val< BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While changing the parameter of the bno055_t + * consider the following point: + * Changing the reference value of the parameter + * will changes the local copy or local reference + * make sure your changes will not + * affect the reference value of the parameter + * (Better case don't change the reference value of the parameter) + */ +BNO055_RETURN_FUNCTION_TYPE bno055_init(struct bno055_t *bno055); +/*! + * @brief + * This API gives data to the given register and + * the data is written in the corresponding register address + * + * @param addr_u8 : Address of the register + * @param data_u8 : Data to be written to the register + * @param len_u8 : Length of the Data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * +*/ +BNO055_RETURN_FUNCTION_TYPE bno055_write_register(u8 addr_u8, +u8 *data_u8, u8 len_u8); +/*! + * @brief This API reads the data from + * the given register address + * + * @param addr_u8 : Address of the register + * @param data_u8 : address of the variable, + * read value will be kept + * @param len_u8 : Length of the data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_register(u8 addr_u8, +u8 *data_u8, u8 len_u8); +/*! + * @brief This API reads chip id + * from register 0x00 it is a byte of data + * + * + * @param chip_id_u8 : The chip id value 0xA0 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_chip_id(u8 *chip_id_u8); +/*! + * @brief This API reads software revision id + * from register 0x04 and 0x05 it is a two byte of data + * + * @param sw_id_u8 : The SW revision id + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_sw_rev_id(u16 *sw_id_u8); +/*! + * @brief This API reads page id + * from register 0x07 it is a byte of data + * + * + * @param page_id_u8 : The value of page id + * + * BNO055_PAGE_ZERO -> 0x00 + * BNO055_PAGE_ONE -> 0x01 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_page_id(u8 *page_id_u8); +/*! + * @brief This API used to write + * the page id register 0x07 + * + * @param page_id_u8 : The value of page id + * + * BNO055_PAGE_ZERO -> 0x00 + * BNO055_PAGE_ONE -> 0x01 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_page_id(u8 page_id_u8); +/*! + * @brief This API reads accel revision id + * from register 0x01 it is a byte of value + * + * @param accel_rev_id_u8 : The accel revision id 0xFB + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_rev_id( +u8 *accel_rev_id_u8); +/*! + * @brief This API reads mag revision id + * from register 0x02 it is a byte of value + * + * @param mag_rev_id_u8 : The mag revision id 0x32 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_rev_id( +u8 *mag_rev_id_u8); +/*! + * @brief This API reads gyro revision id + * from register 0x03 it is a byte of value + * + * @param gyro_rev_id_u8 : The gyro revision id 0xF0 + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_rev_id( +u8 *gyro_rev_id_u8); +/*! + * @brief This API used to read boot loader revision id + * from register 0x06 it is a byte of value + * + * @param bl_rev_id_u8 : The boot loader revision id + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_bl_rev_id( +u8 *bl_rev_id_u8); +/**************************************************/ +/**\name ACCEL DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads acceleration data X values + * from register 0x08 and 0x09 it is a two byte data + * + * + * + * + * @param accel_x_s16 : The X raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_x(s16 *accel_x_s16); +/*! + * @brief This API reads acceleration data Y values + * from register 0x0A and 0x0B it is a two byte data + * + * + * + * + * @param accel_y_s16 : The Y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_y(s16 *accel_y_s16); +/*! + * @brief This API reads acceleration data z values + * from register 0x0C and 0x0D it is a two byte data + * + * + * + * + * @param accel_z_s16 : The z raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_z(s16 *accel_z_s16); +/*! + * @brief This API reads acceleration data xyz values + * from register 0x08 to 0x0D it is a six byte data + * + * + * @param accel : The value of accel xyz data + * + * Parameter | result + * --------- | ----------------- + * x | The accel x data + * y | The accel y data + * z | The accel z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_xyz( +struct bno055_accel_t *accel); +/**************************************************/ +/**\name MAG DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads mag data x values + * from register 0x0E and 0x0F it is a two byte data + * + * + * + * + * @param mag_x_s16 : The x raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_x(s16 *mag_x_s16); +/*! + * @brief This API reads mag data y values + * from register 0x10 and 0x11 it is a two byte data + * + * + * + * + * @param mag_y_s16 : The y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_y(s16 *mag_y_s16); +/*! + * @brief This API reads mag data z values + * from register 0x12 and 0x13 it is a two byte data + * + * + * + * + * @param mag_z_s16 : The z raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_z(s16 *mag_z_s16); +/*! + * @brief This API reads mag data xyz values + * from register 0x0E to 0x13 it is a six byte data + * + * + * @param mag : The mag xyz values + * + * Parameter | result + * --------- | ----------------- + * x | The mag x data + * y | The mag y data + * z | The mag z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_xyz(struct bno055_mag_t *mag); +/**************************************************/ +/**\name GYRO DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads gyro data x values + * from register 0x14 and 0x15 it is a two byte data + * + * + * + * + * @param gyro_x_s16 : The x raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_x(s16 *gyro_x_s16); +/*! + * @brief This API reads gyro data y values + * from register 0x16 and 0x17 it is a two byte data + * + * + * + * + * @param gyro_y_s16 : The y raw data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_y(s16 *gyro_y_s16); +/*! + * @brief This API reads gyro data z values + * from register 0x18 and 0x19 it is a two byte data + * + * @param gyro_z_s16 : The z raw data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_z(s16 *gyro_z_s16); +/*! + * @brief This API reads gyro data xyz values + * from register 0x14 to 0x19 it is a six byte data + * + * + * @param gyro : The value of gyro xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The gyro x data + * y | The gyro y data + * z | The gyro z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_xyz(struct bno055_gyro_t *gyro); +/**************************************************/ +/**\name EULER DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads gyro data z values + * from register 0x1A and 0x1B it is a two byte data + * + * @param euler_h_s16 : The raw h data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_h(s16 *euler_h_s16); +/*! + * @brief This API reads Euler data r values + * from register 0x1C and 0x1D it is a two byte data + * + * @param euler_r_s16 : The raw r data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_r(s16 *euler_r_s16); +/*! + * @brief This API reads Euler data p values + * from register 0x1E and 0x1F it is a two byte data + * + * @param euler_p_s16 : The raw p data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_p(s16 *euler_p_s16); +/*! + * @brief This API reads Euler data hrp values + * from register 0x1A to 0x1F it is a six byte data + * + * + * @param euler : The Euler hrp data's + * + * Parameter | result + * --------- | ----------------- + * h | The Euler h data + * r | The Euler r data + * p | The Euler p data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_euler_hrp( +struct bno055_euler_t *euler); +/**************************************************/ +/**\name QUATERNION DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads quaternion data w values + * from register 0x20 and 0x21 it is a two byte data + * + * @param quaternion_w_s16 : The raw w data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_w( +s16 *quaternion_w_s16); +/*! + * @brief This API reads quaternion data x values + * from register 0x22 and 0x23 it is a two byte data + * + * @param quaternion_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_x( +s16 *quaternion_x_s16); +/*! + * @brief This API reads quaternion data y values + * from register 0x24 and 0x25 it is a two byte data + * + * @param quaternion_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_y( +s16 *quaternion_y_s16); +/*! + * @brief This API reads quaternion data z values + * from register 0x26 and 0x27 it is a two byte data + * + * @param quaternion_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_z( +s16 *quaternion_z_s16); +/*! + * @brief This API reads Quaternion data wxyz values + * from register 0x20 to 0x27 it is a six byte data + * + * + * @param quaternion : The value of quaternion wxyz data's + * + * Parameter | result + * --------- | ----------------- + * w | The quaternion w data + * x | The quaternion x data + * y | The quaternion y data + * z | The quaternion z data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_quaternion_wxyz( +struct bno055_quaternion_t *quaternion); +/**************************************************/ +/**\name LINEAR ACCEL DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads Linear accel data x values + * from register 0x29 and 0x2A it is a two byte data + * + * @param linear_accel_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_x( +s16 *linear_accel_x_s16); +/*! + * @brief This API reads Linear accel data x values + * from register 0x2B and 0x2C it is a two byte data + * + * @param linear_accel_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_y( +s16 *linear_accel_y_s16); +/*! + * @brief This API reads Linear accel data x values + * from register 0x2C and 0x2D it is a two byte data + * + * @param linear_accel_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_z( +s16 *linear_accel_z_s16); +/*! + * @brief This API reads Linear accel data xyz values + * from register 0x28 to 0x2D it is a six byte data + * + * + * @param linear_accel : The value of linear accel xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The linear accel x data + * y | The linear accel y data + * z | The linear accel z data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_linear_accel_xyz( +struct bno055_linear_accel_t *linear_accel); +/**************************************************/ +/**\name GRAVITY DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads gravity data x values + * from register 0x2E and 0x2F it is a two byte data + * + * @param gravity_x_s16 : The raw x data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_x( +s16 *gravity_x_s16); +/*! + * @brief This API reads gravity data y values + * from register 0x30 and 0x31 it is a two byte data + * + * @param gravity_y_s16 : The raw y data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_y( +s16 *gravity_y_s16); +/*! + * @brief This API reads gravity data z values + * from register 0x32 and 0x33 it is a two byte data + * + * @param gravity_z_s16 : The raw z data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_z( +s16 *gravity_z_s16); +/*! + * @brief This API reads gravity data xyz values + * from register 0x2E to 0x33 it is a six byte data + * + * + * @param gravity : The value of gravity xyz data's + * + * Parameter | result + * --------- | ----------------- + * x | The gravity x data + * y | The gravity y data + * z | The gravity z data + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gravity_xyz( +struct bno055_gravity_t *gravity); +/**************************************************/ +/**\name TEMPERATURE DATA READ FUNCTIONS */ +/**************************************************/ +/*! + * @brief This API reads temperature values + * from register 0x33 it is a byte data + * + * @param temp_s8 : The raw temperature data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_temp_data(s8 *temp_s8); +#ifdef BNO055_FLOAT_ENABLE +/********************************************************************/ +/**\name FUNCTIONS FOR READING ACCEL DATA OUTPUT AS FLOAT PRECISION */ +/********************************************************************/ +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as float + * + * @param accel_x_f : The accel x meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_x_msq( +float *accel_x_f); +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as float + * + * @param accel_y_f : The accel y meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_y_msq( +float *accel_y_f); +/*! + * @brief This API is used to convert the accel z raw data + * to meterpersecseq output as float + * + * @param accel_z_f : The accel z meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_z_msq( +float *accel_z_f); +/*! + * @brief This API is used to convert the accel y raw data + * to millig output as float + * + * @param accel_x_f : The accel y millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_x_mg( +float *accel_x_f); +/*! + * @brief This API is used to convert the accel y raw data + * to millig output as float + * + * @param accel_y_f : The accel y millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_y_mg( +float *accel_y_f); +/*! + * @brief This API is used to convert the accel z raw data + * to millig output as float + * + * @param accel_z_f : The accel z millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_z_mg( +float *accel_z_f); +/*! + * @brief This API is used to convert the accel xyz raw data + * to meterpersecseq output as float + * + * @param accel_xyz : The meterpersecseq data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of accel + * y | meterpersecseq data of accel + * z | meterpersecseq data of accel + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_xyz_msq( +struct bno055_accel_float_t *accel_xyz); +/*! + * @brief This API is used to convert the accel xyz raw data + * to millig output as float + * + * @param accel_xyz : The millig data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | millig data of accel + * y | millig data of accel + * z | millig data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_accel_xyz_mg( +struct bno055_accel_float_t *accel_xyz); +/********************************************************************/ +/**\name FUNCTIONS FOR READING MAG DATA OUTPUT AS FLOAT PRECISION */ +/********************************************************************/ +/*! + * @brief This API is used to convert the mag x raw data + * to microTesla output as float + * + * @param mag_x_f : The mag x microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_x_uT( +float *mag_x_f); +/*! + * @brief This API is used to convert the mag y raw data + * to microTesla output as float + * + * @param mag_y_f : The mag y microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_y_uT( +float *mag_y_f); +/*! + * @brief This API is used to convert the mag z raw data + * to microTesla output as float + * + * @param mag_z_f : The mag z microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_z_uT( +float *mag_z_f); +/*! + * @brief This API is used to convert the mag yz raw data + * to microTesla output as float + * + * @param mag_xyz_data : The microTesla data of mag xyz + * + * Parameter | result + * --------- | ----------------- + * x | microTesla data of mag + * y | microTesla data of mag + * z | microTesla data of mag + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_mag_xyz_uT( +struct bno055_mag_float_t *mag_xyz_data); +/********************************************************************/ +/**\name FUNCTIONS FOR READING GYRO DATA OUTPUT AS FLOAT PRECISION */ +/********************************************************************/ +/*! + * @brief This API is used to convert the gyro x raw data + * to dps output as float + * + * @param gyro_x_f : The gyro x dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_x_dps( +float *gyro_x_f); +/*! + * @brief This API is used to convert the gyro x raw data + * to rps output as float + * + * @param gyro_x_f : The gyro x dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_x_rps( +float *gyro_x_f); +/*! + * @brief This API is used to convert the gyro y raw data + * to dps output as float + * + * @param gyro_y_f : The gyro y dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_y_dps( +float *gyro_y_f); +/*! + * @brief This API is used to convert the gyro y raw data + * to rps output as float + * + * @param gyro_y_f : The gyro y dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_y_rps( +float *gyro_y_f); +/*! + * @brief This API is used to convert the gyro z raw data + * to dps output as float + * + * @param gyro_z_f : The gyro z dps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_z_dps( +float *gyro_z_f); +/*! + * @brief This API is used to convert the gyro z raw data + * to rps output as float + * + * @param gyro_z_f : The gyro z rps float data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_z_rps( +float *gyro_z_f); +/*! + * @brief This API is used to convert the gyro xyz raw data + * to dps output as float + * + * @param gyro_xyz_data : The dps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | dps data of gyro + * y | dps data of gyro + * z | dps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_xyz_dps( +struct bno055_gyro_float_t *gyro_xyz_data); +/*! + * @brief This API is used to convert the gyro xyz raw data + * to rps output as float + * + * @param gyro_xyz_data : The rps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | rps data of gyro + * y | rps data of gyro + * z | rps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gyro_xyz_rps( +struct bno055_gyro_float_t *gyro_xyz_data); +/********************************************************************/ +/**\name FUNCTIONS FOR READING EULER DATA OUTPUT AS FLOAT PRECISION */ +/********************************************************************/ +/*! + * @brief This API is used to convert the Euler h raw data + * to degree output as float + * + * @param euler_h_f : The float value of Euler h degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_h_deg( +float *euler_h_f); +/*! + * @brief This API is used to convert the Euler h raw data + * to radians output as float + * + * @param euler_h_f : The float value of Euler h radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_h_rad( +float *euler_h_f); +/*! + * @brief This API is used to convert the Euler r raw data + * to degree output as float + * + * @param euler_r_f : The float value of Euler r degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_r_deg( +float *euler_r_f); +/*! + * @brief This API is used to convert the Euler r raw data + * to radians output as float + * + * @param euler_r_f : The float value of Euler r radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_r_rad( +float *euler_r_f); +/*! + * @brief This API is used to convert the Euler p raw data + * to degree output as float + * + * @param euler_p_f : The float value of Euler p degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_p_deg( +float *euler_p_f); +/*! + * @brief This API is used to convert the Euler p raw data + * to radians output as float + * + * @param euler_p_f : The float value of Euler p radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_p_rad( +float *euler_p_f); +/*! + * @brief This API is used to convert the Euler hrp raw data + * to degree output as float + * + * @param euler_hpr : The degree data of Euler hrp + * + * Parameter | result + * --------- | ----------------- + * h | degree data of Euler + * r | degree data of Euler + * p | degree data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_hpr_deg( +struct bno055_euler_float_t *euler_hpr); +/*! + * @brief This API is used to convert the Euler xyz raw data + * to radians output as float + * + * @param euler_hpr : The radians data of Euler hrp + * + * Parameter | result + * --------- | ----------------- + * h | radians data of Euler + * r | radians data of Euler + * p | radians data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_euler_hpr_rad( +struct bno055_euler_float_t *euler_hpr); +/***************************************************************************/ +/**\name FUNCTIONS FOR READING LINEAR ACCEL DATA OUTPUT AS FLOAT PRECISION */ +/**************************************************************************/ +/*! + * @brief This API is used to convert the linear + * accel x raw data to meterpersecseq output as float + * + * @param linear_accel_x_f : The float value of linear accel x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_x_msq( +float *linear_accel_x_f); +/*! + * @brief This API is used to convert the linear + * accel y raw data to meterpersecseq output as float + * + * @param linear_accel_y_f : The float value of linear accel y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_y_msq( +float *linear_accel_y_f); +/*! + * @brief This API is used to convert the linear + * accel z raw data to meterpersecseq output as float + * + * @param linear_accel_z_f : The float value of linear accel z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_z_msq( +float *linear_accel_z_f); +/*! + * @brief This API is used to convert the linear accel xyz raw data + * to meterpersecseq output as float + * + * @param linear_accel_xyz : The meterpersecseq data of linear accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of linear accel + * y | meterpersecseq data of linear accel + * z | meterpersecseq data of linear accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_linear_accel_xyz_msq( +struct bno055_linear_accel_float_t *linear_accel_xyz); +/********************************************************************/ +/**\name FUNCTIONS FOR READING GRAVITY DATA OUTPUT AS FLOAT PRECISION */ +/********************************************************************/ +/*! + * @brief This API is used to convert the gravity + * x raw data to meterpersecseq output as float + * + * @param gravity_x_f : The float value of gravity x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_x_msq( +float *gravity_x_f); +/*! + * @brief This API is used to convert the gravity + * y raw data to meterpersecseq output as float + * + * @param gravity_y_f : The float value of gravity y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_y_msq( +float *gravity_y_f); +/*! + * @brief This API is used to convert the gravity + * z raw data to meterpersecseq output as float + * + * @param gravity_z_f : The float value of gravity z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_float_z_msq( +float *gravity_z_f); +/*! + * @brief This API is used to convert the gravity xyz raw data + * to meterpersecseq output as float + * + * @param gravity_xyz : The meterpersecseq data of gravity xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of gravity + * y | meterpersecseq data of gravity + * z | meterpersecseq data of gravity + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_gravity_xyz_msq( +struct bno055_gravity_float_t *gravity_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING TEMPERATURE DATA OUTPUT AS FLOAT PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the temperature + * data to Fahrenheit output as float + * + * @param temp_f : The float value of temperature Fahrenheit + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_temp_fahrenheit( +float *temp_f); +/*! + * @brief This API is used to convert the temperature + * data to Celsius output as float + * + * @param temp_f : The float value of temperature Celsius + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_float_temp_celsius( +float *temp_f); +#endif +#ifdef BNO055_DOUBLE_ENABLE +/**************************************************************************/ +/**\name FUNCTIONS FOR READING ACCEL DATA OUTPUT AS DOUBLE PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the accel x raw data + * to meterpersecseq output as double + * + * @param accel_x_d : The accel x meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_x_msq( +double *accel_x_d); +/*! + * @brief This API is used to convert the accel y raw data + * to meterpersecseq output as double + * + * @param accel_y_d : The accel y meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_y_msq( +double *accel_y_d); +/*! + * @brief This API is used to convert the accel z raw data + * to meterpersecseq output as double + * + * @param accel_z_d : The accel z meterpersecseq data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_z_msq( +double *accel_z_d); +/*! + * @brief This API is used to convert the accel x raw data + * to millig output as double + * + * @param accel_x_d : The accel x millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_x_mg( +double *accel_x_d); +/*! + * @brief This API is used to convert the accel y raw data + * to millig output as double + * + * @param accel_y_d : The accel y millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_y_mg( +double *accel_y_d); +/*! + * @brief This API is used to convert the accel z raw data + * to millig output as double + * + * @param accel_z_d : The accel z millig data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_z_mg( +double *accel_z_d); +/*! + * @brief This API is used to convert the accel xyz raw data + * to meterpersecseq output as double + * + * @param accel_xyz : The meterpersecseq data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of accel + * y | meterpersecseq data of accel + * z | meterpersecseq data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_xyz_msq( +struct bno055_accel_double_t *accel_xyz); +/*! + * @brief This API is used to convert the accel xyz raw data + * to millig output as double + * + * @param accel_xyz : The millig data of accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | millig data of accel + * y | millig data of accel + * z | millig data of accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_accel_xyz_mg( +struct bno055_accel_double_t *accel_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING MAG DATA OUTPUT AS DOUBLE PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the mag x raw data + * to microTesla output as double + * + * @param mag_x_d : The mag x microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_x_uT( +double *mag_x_d); +/*! + * @brief This API is used to convert the mag x raw data + * to microTesla output as double + * + * @param mag_y_d : The mag x microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_y_uT( +double *mag_y_d); +/*! + * @brief This API is used to convert the mag z raw data + * to microTesla output as double + * + * @param mag_z_d : The mag z microTesla data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_z_uT( +double *mag_z_d); +/*! + * @brief This API is used to convert the mag yz raw data + * to microTesla output as double + * + * @param mag_xyz : The microTesla data of mag xyz + * + * Parameter | result + * --------- | ----------------- + * x | microTesla data of mag + * y | microTesla data of mag + * z | microTesla data of mag + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_mag_xyz_uT( +struct bno055_mag_double_t *mag_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING GYRO DATA OUTPUT AS DOUBLE PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the gyro x raw data + * to dps output as double + * + * @param gyro_x_d : The gyro x dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_x_dps( +double *gyro_x_d); +/*! + * @brief This API is used to convert the gyro y raw data + * to dps output as double + * + * @param gyro_y_d : The gyro y dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_y_dps( +double *gyro_y_d); +/*! + * @brief This API is used to convert the gyro z raw data + * to dps output as double + * + * @param gyro_z_d : The gyro z dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_z_dps( +double *gyro_z_d); +/*! + * @brief This API is used to convert the gyro x raw data + * to rps output as double + * + * @param gyro_x_d : The gyro x dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_x_rps( +double *gyro_x_d); +/*! + * @brief This API is used to convert the gyro y raw data + * to rps output as double + * + * @param gyro_y_d : The gyro y dps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_y_rps( +double *gyro_y_d); +/*! + * @brief This API is used to convert the gyro z raw data + * to rps output as double + * + * @param gyro_z_d : The gyro z rps double data + * + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_z_rps( +double *gyro_z_d); +/*! + * @brief This API is used to convert the gyro xyz raw data + * to dps output as double + * + * @param gyro_xyz : The dps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | dps data of gyro + * y | dps data of gyro + * z | dps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_xyz_dps( +struct bno055_gyro_double_t *gyro_xyz); +/*! + * @brief This API is used to convert the gyro xyz raw data + * to rps output as double + * + * @param gyro_xyz : The rps data of gyro xyz + * + * Parameter | result + * --------- | ----------------- + * x | rps data of gyro + * y | rps data of gyro + * z | rps data of gyro + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gyro_xyz_rps( +struct bno055_gyro_double_t *gyro_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING EULER DATA OUTPUT AS DOUBLE PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the Euler h raw data + * to degree output as double + * + * @param euler_h_d : The double value of Euler h degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_h_deg( +double *euler_h_d); +/*! + * @brief This API is used to convert the Euler p raw data + * to degree output as double + * + * @param euler_p_d : The double value of Euler p degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_p_deg( +double *euler_p_d); +/*! + * @brief This API is used to convert the Euler r raw data + * to degree output as double + * + * @param euler_r_d : The double value of Euler r degree + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_r_deg( +double *euler_r_d); +/*! + * @brief This API is used to convert the Euler h raw data + * to radians output as double + * + * @param euler_h_d : The double value of Euler h radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_h_rad( +double *euler_h_d); +/*! + * @brief This API is used to convert the Euler p raw data + * to radians output as double + * + * @param euler_p_d : The double value of Euler p radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_p_rad( +double *euler_p_d); +/*! + * @brief This API is used to convert the Euler r raw data + * to radians output as double + * + * @param euler_r_d : The double value of Euler r radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_r_rad( +double *euler_r_d); +/*! + * @brief This API is used to convert the Euler hpr raw data + * to degree output as double + * + * @param euler_hpr : The degree data of Euler hpr + * + * Parameter | result + * --------- | ----------------- + * h | degree data of Euler + * r | degree data of Euler + * p | degree data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_hpr_deg( +struct bno055_euler_double_t *euler_hpr); +/*! + * @brief This API is used to convert the Euler hpr raw data + * to radians output as double + * + * @param euler_hpr : The radians data of Euler hpr + * + * Parameter | result + * --------- | ----------------- + * h | radians data of Euler + * r | radians data of Euler + * p | radians data of Euler + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_euler_hpr_rad( +struct bno055_euler_double_t *euler_hpr); +/****************************************************************************/ +/**\name FUNCTIONS FOR READING LINEAR ACCEL DATA OUTPUT AS DOUBLE PRECISION */ +/****************************************************************************/ +/*! + * @brief This API is used to convert the linear + * accel x raw data to meterpersecseq output as double + * + * @param linear_accel_x_d : The double value of + * linear accel x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_x_msq( +double *linear_accel_x_d); +/*! + * @brief This API is used to convert the linear + * accel y raw data to meterpersecseq output as double + * + * @param linear_accel_y_d : The double value of + * linear accel y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_y_msq( +double *linear_accel_y_d); +/*! + * @brief This API is used to convert the linear + * accel z raw data to meterpersecseq output as double + * + * @param linear_accel_z_d : The double value of + * linear accel z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_z_msq( +double *linear_accel_z_d); +/*! + * @brief This API is used to convert the linear accel xyz raw data + * to meterpersecseq output as double + * + * @param linear_accel_xyz : The meterpersecseq data of linear accel xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of linear accel + * y | meterpersecseq data of linear accel + * z | meterpersecseq data of linear accel + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_linear_accel_xyz_msq( +struct bno055_linear_accel_double_t *linear_accel_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING GRAVITY DATA OUTPUT AS DOUBLE PRECISION */ +/*************************************************************************/ +/*! + * @brief This API is used to convert the gravity + * x raw data to meterpersecseq output as double + * + * @param gravity_x_d : The double value of gravity x meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_x_msq( +double *gravity_x_d); +/*! + * @brief This API is used to convert the gravity + * y raw data to meterpersecseq output as double + * + * @param gravity_y_d : The double value of gravity y meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_y_msq( +double *gravity_y_d); +/*! + * @brief This API is used to convert the gravity + * z raw data to meterpersecseq output as double + * + * @param gravity_z_d : The double value of gravity z meterpersecseq + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_gravity_double_z_msq( +double *gravity_z_d); +/*! + * @brief This API is used to convert the gravity xyz raw data + * to meterpersecseq output as double + * + * @param gravity_xyz : The meterpersecseq data of gravity xyz + * + * Parameter | result + * --------- | ----------------- + * x | meterpersecseq data of gravity + * y | meterpersecseq data of gravity + * z | meterpersecseq data of gravity + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_gravity_xyz_msq( +struct bno055_gravity_double_t *gravity_xyz); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING TEMPERATURE DATA OUTPUT AS DOUBLE PRECISION*/ +/*************************************************************************/ +/*! + * @brief This API is used to convert the temperature + * data to Fahrenheit output as double + * + * @param temp_d : The double value of temperature Fahrenheit + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_temp_fahrenheit( +double *temp_d); +/*! + * @brief This API is used to convert the temperature + * data to Celsius output as double + * + * @param temp_d : The double value of temperature Celsius + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_convert_double_temp_celsius( +double *temp_d); +#endif +/**************************************************************************/ +/**\name FUNCTIONS FOR READING ACCEL,MAG,GYRO AND SYSTEM CALIBRATION STATUS*/ +/*************************************************************************/ +/*! + * @brief This API used to read + * mag calibration status from register from 0x35 bit 0 and 1 + * + * @param mag_calib_u8 : The value of mag calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_calib_stat( +u8 *mag_calib_u8); +/*! + * @brief This API used to read + * accel calibration status from register from 0x35 bit 2 and 3 + * + * @param accel_calib_u8 : The value of accel calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_calib_stat( +u8 *accel_calib_u8); +/*! + * @brief This API used to read + * gyro calibration status from register from 0x35 bit 4 and 5 + * + * @param gyro_calib_u8 : The value of gyro calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_calib_stat( +u8 *gyro_calib_u8); +/*! + * @brief This API used to read + * system calibration status from register from 0x35 bit 6 and 7 + * + * @param sys_calib_u8 : The value of system calib status + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_calib_stat( +u8 *sys_calib_u8); +/******************************************************************/ +/**\name FUNCTIONS FOR READING ACCEL,MAG,GYRO AND SYSTEM SELF TEST */ +/******************************************************************/ +/*! + * @brief This API used to read + * self test of accel from register from 0x36 bit 0 + * + * @param selftest_accel_u8 : The value of self test of accel + * + * selftest_accel_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_accel( +u8 *selftest_accel_u8); +/*! + * @brief This API used to read + * self test of mag from register from 0x36 bit 1 + * + * @param selftest_mag_u8 : The value of self test of mag + * + * selftest_mag_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_mag( +u8 *selftest_mag_u8); +/*! + * @brief This API used to read + * self test of gyro from register from 0x36 bit 2 + * + * @param selftest_gyro_u8 : The value of self test of gyro + * + * selftest_gyro_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_gyro( +u8 *selftest_gyro_u8); +/*! + * @brief This API used to read + * self test of micro controller from register from 0x36 bit 3 + * + * @param selftest_mcu_u8 : The value of self test of micro controller + * + * selftest_mcu_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates test failed + * 0x01 | indicated test passed + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest_mcu( +u8 *selftest_mcu_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR READING GYRO INTERRUPT STATUS */ +/*****************************************************/ +/*! + * @brief This API used to read the stat_s8 of + * gyro anymotion interrupt from register from 0x37 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * + * gyro_any_motion_u8 | result + * -------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt can be BNO055_BIT_ENABLE + * by the following APIs + * + * bno055_set_intr_mask_gyro_any_motion() + * + * bno055_set_intr_gyro_any_motion() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_gyro_any_motion( +u8 *gyro_any_motion_u8); +/*! + * @brief This API used to read the stat_s8 of + * gyro highrate interrupt from register from 0x37 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * + * gyro_highrate_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_gyro_highrate() + * + * bno055_set_intr_gyro_highrate() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_gyro_highrate( +u8 *gyro_highrate_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR READING ACCEL INTERRUPT STATUS */ +/*****************************************************/ +/*! + * @brief This API used to read the status of + * accel highg interrupt from register from 0x37 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * + * accel_high_g_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_high_g() + * + * bno055_set_intr_accel_high_g() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_high_g( +u8 *accel_high_g_u8); +/*! + * @brief This API used to read the stat_s8 of + * accel anymotion interrupt from register from 0x37 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * + * accel_any_motion_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_any_motion() + * + * bno055_set_intr_accel_any_motion() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_any_motion( +u8 *accel_any_motion_u8); +/*! + * @brief This API used to read the stat_s8 of + * accel nomotion/slowmotion interrupt from register from 0x37 bit 6 + * + * @param accel_no_motion_u8 : + * The value of accel nomotion/slowmotion interrupt + * + * accel_no_motion_u8 | result + * ------------------- | --------------------- + * 0x00 | indicates no interrupt triggered + * 0x01 | indicates interrupt triggered + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel nomotion/slowmotion interrupt can be configured + * by the following APIs + * + * bno055_set_intr_mask_accel_nomotion() + * + * bno055_set_intr_accel_nomotion() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_stat_accel_no_motion( +u8 *accel_no_motion_u8); +/**************************************************************************/ +/**\name FUNCTIONS FOR READING SYSTEM CLOCK, STATUS AND BNO055_ERROR CODE */ +/*************************************************************************/ +/*! + * @brief This API is used to read status of main clock + * from the register 0x38 bit 0 + * + * @param stat_main_clk_u8 : the status of main clock + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_stat_main_clk( +u8 *stat_main_clk_u8); +/*! + * @brief This API is used to read system status + * code from the register 0x39 it is a byte of data + * + * @param sys_stat_u8 : the status of system + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_stat_code( +u8 *sys_stat_u8); +/*! + * @brief This API is used to read system BNO055_ERROR + * code from the register 0x3A it is a byte of data + * + * @param sys_error_u8 : The value of system BNO055_ERROR code + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_error_code( +u8 *sys_error_u8); +/********************************************/ +/**\name FUNCTIONS FOR ACCEL UNIT SELECTION */ +/********************************************/ +/*! + * @brief This API used to read the accel unit + * from register from 0x3B bit 0 + * + * @param accel_unit_u8 : The value of accel unit + * + * accel_unit_u8 | result + * ------------- | --------------- + * 0x00 | BNO055_ACCEL_UNIT_MSQ + * 0x01 | BNO055_ACCEL_UNIT_MG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_unit( +u8 *accel_unit_u8); +/*! + * @brief This API used to write the accel unit + * from register from 0x3B bit 0 + * + * @param accel_unit_u8 : The value of accel unit + * + * accel_unit_u8 | result + * ------------- | --------------- + * 0x00 | BNO055_ACCEL_UNIT_MSQ + * 0x01 | BNO055_ACCEL_UNIT_MG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_unit( +u8 accel_unit_u8); +/********************************************/ +/**\name FUNCTIONS FOR GYRO UNIT SELECTION */ +/********************************************/ +/*! + * @brief This API used to read the gyro unit + * from register from 0x3B bit 1 + * + * @param gyro_unit_u8 : The value of accel unit + * + * gyro_unit_u8 | result + * ------------- | ----------- + * 0x00 | BNO055_GYRO_UNIT_DPS + * 0x01 | BNO055_GYRO_UNIT_RPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_unit( +u8 *gyro_unit_u8); +/*! + * @brief This API used to write the gyro unit + * from register from 0x3B bit 1 + * + * @param gyro_unit_u8 : The value of accel unit + * + * gyro_unit_u8 | result + * ------------- | ----------- + * 0x00 | BNO055_GYRO_UNIT_DPS + * 0x01 | BNO055_GYRO_UNIT_RPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_unit(u8 gyro_unit_u8); +/********************************************/ +/**\name FUNCTIONS FOR EULER UNIT SELECTION */ +/********************************************/ +/*! + * @brief This API used to read the Euler unit + * from register from 0x3B bit 2 + * + * @param euler_unit_u8 : The value of accel unit + * + * euler_unit_u8 | result + * -------------- | ----------- + * 0x00 | BNO055_EULER_UNIT_DEG + * 0x01 | BNO055_EULER_UNIT_RAD + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_euler_unit( +u8 *euler_unit_u8); +/*! + * @brief This API used to write the Euler unit + * from register from 0x3B bit 2 + * + * @param euler_unit_u8 : The value of Euler unit + * + * euler_unit_u8 | result + * -------------- | ----------- + * 0x00 | BNO055_EULER_UNIT_DEG + * 0x01 | BNO055_EULER_UNIT_RAD + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_euler_unit(u8 euler_unit_u8); +/********************************************/ +/**\name FUNCTIONS FOR TILT UNIT SELECTION */ +/********************************************/ +/*! + * @brief This API used to write the tilt unit + * from register from 0x3B bit 3 + * + * @param tilt_unit_u8 : The value of tilt unit + * + * tilt_unit_u8 | result + * --------------- | --------- + * 0x00 | degrees + * 0x01 | radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_tilt_unit( +u8 *tilt_unit_u8); +/*! + * @brief This API used to write the tilt unit + * from register from 0x3B bit 3 + * + * @param tilt_unit_u8 : The value of tilt unit + * + * tilt_unit_u8 | result + * --------------- | --------- + * 0x00 | degrees + * 0x01 | radians + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + * + * \return Communication results + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_tilt_unit( +u8 tilt_unit_u8); +/**************************************************/ +/**\name FUNCTIONS FOR TEMPERATURE UNIT SELECTION */ +/**************************************************/ +/*! + * @brief This API used to read the temperature unit + * from register from 0x3B bit 4 + * + * @param temp_unit_u8 : The value of temperature unit + * + * temp_unit_u8 | result + * ----------- | -------------- + * 0x00 | BNO055_TEMP_UNIT_CELSIUS + * 0x01 | BNO055_TEMP_UNIT_FAHRENHEIT + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_temp_unit( +u8 *temp_unit_u8); +/*! + * @brief This API used to write the temperature unit + * from register from 0x3B bit 4 + * + * @param temp_unit_u8 : The value of temperature unit + * + * temp_unit_u8 | result + * ----------- | -------------- + * 0x00 | BNO055_TEMP_UNIT_CELSIUS + * 0x01 | BNO055_TEMP_UNIT_FAHRENHEIT + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_temp_unit( +u8 temp_unit_u8); +/**************************************************/ +/**\name FUNCTIONS FOR DATA OUTPUT FORMAT SELECT */ +/**************************************************/ +/*! + * @brief This API used to read the current selected orientation mode + * from register from 0x3B bit 7 + * + * @param data_output_format_u8 : The value of data output format + * + * data_output_format_u8 | result + * -------------------- | -------- + * 0x00 | Windows + * 0x01 | Android + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_data_output_format( +u8 *data_output_format_u8); +/*! + * @brief This API used to read the current selected orientation mode + * from register from 0x3B bit 7 + * + * @param data_output_format_u8 : The value of data output format + * + * data_output_format_u8 | result + * -------------------- | -------- + * 0x00 | Windows + * 0x01 | Android + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_data_output_format( +u8 data_output_format_u8); +/**************************************************/ +/**\name FUNCTIONS FOR DATA OPERATION MODE */ +/**************************************************/ +/*! @brief This API used to read the operation mode + * from register from 0x3D bit 0 to 3 + * + * @param operation_mode_u8 : The value of operation mode + * + * operation_mode_u8 | result | comments + * ----------|----------------------------|---------------------------- + * 0x00 | BNO055_OPERATION_MODE_CONFIG | Configuration mode + * 0x01 | BNO055_OPERATION_MODE_ACCONLY | Reads accel data alone + * 0x02 | BNO055_OPERATION_MODE_MAGONLY | Reads mag data alone + * 0x03 | BNO055_OPERATION_MODE_GYRONLY | Reads gyro data alone + * 0x04 | BNO055_OPERATION_MODE_ACCMAG | Reads accel and mag data + * 0x05 | BNO055_OPERATION_MODE_ACCGYRO | Reads accel and gyro data + * 0x06 | BNO055_OPERATION_MODE_MAGGYRO | Reads accel and mag data + * 0x07 | OPERATION_MODE_ANY_MOTION | Reads accel mag and gyro data + * 0x08 | BNO055_OPERATION_MODE_IMUPLUS | Inertial measurement unit + * - | - | Reads accel,gyro and fusion data + * 0x09 | BNO055_OPERATION_MODE_COMPASS | Reads accel, mag data + * - | - | and fusion data + * 0x0A | BNO055_OPERATION_MODE_M4G | Reads accel, mag data + * - | - | and fusion data + * 0x0B | BNO055_OPERATION_MODE_NDOF_FMC_OFF| Nine degrees of freedom with + * - | - | fast magnetic calibration + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * 0x0C | BNO055_OPERATION_MODE_NDOF | Nine degrees of freedom + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note In the config mode, all sensor and fusion data + * becomes zero and it is mainly derived + * to configure the various settings of the BNO + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_operation_mode( +u8 *operation_mode_u8); +/*! @brief This API used to write the operation mode + * from register from 0x3D bit 0 to 3 + * + * @param operation_mode_u8 : The value of operation mode + * + * operation_mode_u8 | result | comments + * ---------|-----------------------------------|-------------------------- + * 0x00 | BNO055_OPERATION_MODE_CONFIG | Configuration mode + * 0x01 | BNO055_OPERATION_MODE_ACCONLY | Reads accel data alone + * 0x02 | BNO055_OPERATION_MODE_MAGONLY | Reads mag data alone + * 0x03 | BNO055_OPERATION_MODE_GYRONLY | Reads gyro data alone + * 0x04 | BNO055_OPERATION_MODE_ACCMAG | Reads accel and mag data + * 0x05 | BNO055_OPERATION_MODE_ACCGYRO | Reads accel and gyro data + * 0x06 | BNO055_OPERATION_MODE_MAGGYRO | Reads accel and mag data + * 0x07 | OPERATION_MODE_ANY_MOTION | Reads accel mag and + * | - | gyro data + * 0x08 | BNO055_OPERATION_MODE_IMUPLUS | Inertial measurement unit + * - | | Reads accel,gyro and + * | - | fusion data + * 0x09 | BNO055_OPERATION_MODE_COMPASS | Reads accel, mag data + * - | - | and fusion data + * 0x0A | BNO055_OPERATION_MODE_M4G | Reads accel, mag data + * - | - | and fusion data + * 0x0B | BNO055_OPERATION_MODE_NDOF_FMC_OFF| Nine degrees of freedom with + * - | - | fast magnetic calibration + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * 0x0C | BNO055_OPERATION_MODE_NDOF | Nine degrees of freedom + * - | - | Reads accel,mag, gyro + * - | - | and fusion data + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note In the config mode, all sensor and fusion data + * becomes zero and it is mainly derived + * to configure the various settings of the BNO + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_operation_mode(u8 operation_mode_u8); +/**************************************************/ +/**\name FUNCTIONS FOR POWER MODE */ +/**************************************************/ +/*! @brief This API used to read the power mode + * from register from 0x3E bit 0 to 1 + * + * @param power_mode_u8 : The value of power mode + * + * power_mode_u8| result | comments + * ---------|---------------------------|------------------------------------- + * 0x00 |BNO055_POWER_MODE_NORMAL | In the NORMAL mode the register + * - | - | map and the internal peripherals + * - | - | of the MCU are always + * - | - | operative in this mode + * 0x01 |BNO055_POWER_MODE_LOWPOWER | This is first level of power + * | - | saving mode + * 0x02 |BNO055_POWER_MODE_SUSPEND | In suspend mode the system is + * - | - | paused and all the sensors and + * - | - | the micro controller are + * - | - | put into sleep mode. + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note For detailed about LOWPOWER mode + * refer data sheet 3.4.2 + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_power_mode( +u8 *power_mode_u8); +/*! @brief This API used to write the power mode + * from register from 0x3E bit 0 to 1 + * + * @param power_mode_u8 : The value of power mode + * + * + * power_mode_u8| result | comments + * -------|----------------------------|--------------------------------- + * 0x00 | BNO055_POWER_MODE_NORMAL | In the NORMAL mode the register + * - | - | map and the internal peripherals + * - | - | of the MCU are always + * - | - | operative in this mode + * 0x01 | BNO055_POWER_MODE_LOWPOWER | This is first level of power + * | - | saving mode + * 0x02 | BNO055_POWER_MODE_SUSPEND | In suspend mode the system is + * - | - | paused and all the sensors and + * - | - | the micro controller are + * - | - | put into sleep mode. + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note For detailed about LOWPOWER mode + * refer data sheet 3.4.2 + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_power_mode(u8 power_mode_u8); +/**************************************************/ +/**\name FUNCTIONS FOR RESET INTERRUPT */ +/**************************************************/ +/*! + * @brief This API used to read the reset interrupt + * from register from 0x3F bit 6 + * It resets all the interrupt bit and interrupt output + * + * @param intr_rst_u8 : The value of reset interrupt + * + * intr_rst_u8 | result + * -------------|---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_rst( +u8 *intr_rst_u8); +/*! + * @brief This API used to write the reset interrupt + * from register from 0x3F bit 6 + * It resets all the interrupt bit and interrupt output + * + * @param intr_rst_u8 : The value of reset interrupt + * + * intr_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_rst(u8 intr_rst_u8); +/**************************************************/ +/**\name FUNCTIONS FOR CLOCK SOURCE */ +/**************************************************/ +/*! + * @brief This API used to read the clk source + * from register from 0x3F bit 7 + * + * @param clk_src_u8 : The value of clk source + * + * clk_src_u8 | result + * -------------|---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_clk_src( +u8 *clk_src_u8); +/*! + * @brief This API used to write the clk source + * from register from 0x3F bit 7 + * + * @param clk_src_u8 : The value of clk source + * + * clk_src_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_clk_src(u8 clk_src_u8); +/**************************************************/ +/**\name FUNCTIONS FOR RESET SYSTEM */ +/**************************************************/ +/*! + * @brief This API used to read the reset system + * from register from 0x3F bit 5 + * + * @param sys_rst_u8 : The value of reset system + * + * sys_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It resets the whole system + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_sys_rst( +u8 *sys_rst_u8); +/*! + * @brief This API used to write the reset system + * from register from 0x3F bit 5 + * + * @param sys_rst_u8 : The value of reset system + * + * sys_rst_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It resets the whole system + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_sys_rst(u8 sys_rst_u8); +/**************************************************/ +/**\name FUNCTIONS FOR SELF TEST */ +/**************************************************/ +/*! + * @brief This API used to read the self test + * from register from 0x3F bit 0 + * + * @param selftest_u8 : The value of self test + * + * selftest_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It triggers the self test + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_selftest( +u8 *selftest_u8); +/*! + * @brief This API used to write the self test + * from register from 0x3F bit 0 + * + * @param selftest_u8 : The value of self test + * + * selftest_u8 | result + * -------------- |---------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note It triggers the self test + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_selftest(u8 selftest_u8); +/**************************************************/ +/**\name FUNCTIONS FOR TEMPERATURE SOURCE */ +/**************************************************/ +/*! + * @brief This API used to read the temperature source + * from register from 0x40 bit 0 and 1 + * + * @param temp_source_u8 : The value of selected temperature source + * + * temp_source_u8 | result + * ---------------- |--------------- + * 0x00 | BNO055_ACCEL_TEMP_EN + * 0X01 | BNO055_GYRO_TEMP_EN + * 0X03 | BNO055_MCU_TEMP_EN + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_temp_source( +u8 *temp_source_u8); +/*! + * @brief This API used to write the temperature source + * from register from 0x40 bit 0 and 1 + * + * @param temp_source_u8 : The value of selected temperature source + * + * temp_source_u8 | result + * ---------------- |--------------- + * 0x00 | BNO055_ACCEL_TEMP_EN + * 0X01 | BNO055_GYRO_TEMP_EN + * 0X03 | BNO055_MCU_TEMP_EN + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_temp_source(u8 temp_source_u8); +/**************************************************/ +/**\name APIs FOR AXIS REMAP */ +/**************************************************/ +/*! + * @brief This API used to read the axis remap value + * from register from 0x41 bit 0 and 5 + * + * @param remap_axis_u8 : The value of axis remapping + * + * remap_axis_u8 | result | comments + * ------------|-------------------|------------ + * 0X21 | BNO055_REMAP_X_Y | Z=Z;X=Y;Y=X + * 0X18 | BNO055_REMAP_Y_Z | X=X;Y=Z;Z=Y + * 0X06 | BNO055_REMAP_Z_X | Y=Y;X=Z;Z=X + * 0X12 | BNO055_REMAP_X_Y_Z_TYPE0 | X=Z;Y=X;Z=Y + * 0X09 | BNO055_REMAP_X_Y_Z_TYPE1 | X=Y;Y=Z;Z=X + * 0X24 | BNO055_DEFAULT_AXIS | X=X;Y=Y;Z=Z + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : For axis sign remap refer the following APIs + * x-axis : + * + * bno055_set_x_remap_sign() + * + * y-axis : + * + * bno055_set_y_remap_sign() + * + * z-axis : + * + * bno055_set_z_remap_sign() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_axis_remap_value( +u8 *remap_axis_u8); +/*! + * @brief This API used to write the axis remap value + * from register from 0x41 bit 0 and 5 + * + * @param remap_axis_u8 : The value of axis remapping + * + * remap_axis_u8 | result | comments + * ------------|--------------------------|------------ + * 0X21 | BNO055_REMAP_X_Y | Z=Z;X=Y;Y=X + * 0X18 | BNO055_REMAP_Y_Z | X=X;Y=Z;Z=Y + * 0X06 | BNO055_REMAP_Z_X | Y=Y;X=Z;Z=X + * 0X12 | BNO055_REMAP_X_Y_Z_TYPE0 | X=Z;Y=X;Z=Y + * 0X09 | BNO055_REMAP_X_Y_Z_TYPE1 | X=Y;Y=Z;Z=X + * 0X24 | BNO055_DEFAULT_AXIS | X=X;Y=Y;Z=Z + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : For axis sign remap refer the following APIs + * x-axis : + * + * bno055_set_x_remap_sign() + * + * y-axis : + * + * bno055_set_y_remap_sign() + * + * z-axis : + * + * bno055_set_z_remap_sign() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_axis_remap_value( +u8 remap_axis_u8); +/**************************************************/ +/**\name APIs FOR AXIS REMAP SIGN */ +/**************************************************/ +/*! + * @brief This API used to read the x-axis remap + * sign from register from 0x42 bit 2 + * + * @param remap_x_sign_u8 : The value of x-axis remap sign + * + * remap_x_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_x_sign( +u8 *remap_x_sign_u8); +/*! + * @brief This API used to write the x-axis remap + * sign from register from 0x42 bit 2 + * + * @param remap_x_sign_u8 : The value of x-axis remap sign + * + * remap_x_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_x_sign( +u8 remap_x_sign_u8); +/*! + * @brief This API used to read the y-axis remap + * sign from register from 0x42 bit 1 + * + * @param remap_y_sign_u8 : The value of y-axis remap sign + * + * remap_y_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_y_sign( +u8 *remap_y_sign_u8); +/*! + * @brief This API used to write the y-axis remap + * sign from register from 0x42 bit 1 + * + * @param remap_y_sign_u8 : The value of y-axis remap sign + * + * remap_y_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_y_sign( +u8 remap_y_sign_u8); +/*! + * @brief This API used to read the z-axis remap + * sign from register from 0x42 bit 0 + * + * @param remap_z_sign_u8 : The value of z-axis remap sign + * + * remap_z_sign_u8 | result + * ------------------- |-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_remap_z_sign( +u8 *remap_z_sign_u8); +/*! + * @brief This API used to write the z-axis remap + * sign from register from 0x42 bit 0 + * + * @param remap_z_sign_u8 : The value of z-axis remap sign + * + * remap_z_sign_u8 | result + * ------------------|-------------------- + * 0X00 | BNO055_REMAP_AXIS_POSITIVE + * 0X01 | BNO055_REMAP_AXIS_NEGATIVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_remap_z_sign( +u8 remap_z_sign_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR SOFT IRON CALIBRATION MATRIX */ +/*****************************************************/ +/*! + * @brief This API is used to read soft iron calibration matrix + * from the register 0x43 to 0x53 it is a 18 bytes of data + * + * @param sic_matrix : The value of soft iron calibration matrix + * + * sic_matrix | result + * --------------------|---------------------------------- + * sic_0 | soft iron calibration matrix zero + * sic_1 | soft iron calibration matrix one + * sic_2 | soft iron calibration matrix two + * sic_3 | soft iron calibration matrix three + * sic_4 | soft iron calibration matrix four + * sic_5 | soft iron calibration matrix five + * sic_6 | soft iron calibration matrix six + * sic_7 | soft iron calibration matrix seven + * sic_8 | soft iron calibration matrix eight + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : Each soft iron calibration matrix range from -32768 to +32767 + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_sic_matrix( +struct bno055_sic_matrix_t *sic_matrix); +/*! + * @brief This API is used to write soft iron calibration matrix + * from the register 0x43 to 0x53 it is a 18 bytes of data + * + * @param sic_matrix : The value of soft iron calibration matrix + * + * sic_matrix | result + * --------------------|---------------------------------- + * sic_0 | soft iron calibration matrix zero + * sic_1 | soft iron calibration matrix one + * sic_2 | soft iron calibration matrix two + * sic_3 | soft iron calibration matrix three + * sic_4 | soft iron calibration matrix four + * sic_5 | soft iron calibration matrix five + * sic_6 | soft iron calibration matrix six + * sic_7 | soft iron calibration matrix seven + * sic_8 | soft iron calibration matrix eight + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note : Each soft iron calibration matrix range from -32768 to +32767 + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_sic_matrix( +struct bno055_sic_matrix_t *sic_matrix); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL OFFSET AND RADIUS */ +/*****************************************************/ +/*! + * @brief This API is used to read accel offset and accel radius + * offset form register 0x55 to 0x5A and radius form 0x67 and 0x68 + * + * @param accel_offset : The value of accel offset and radius + * + * bno055_accel_offset_t | result + * ------------------- | ---------------- + * x | accel offset x + * y | accel offset y + * z | accel offset z + * r | accel offset r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the accel offset varies based on + * the G-range of accel sensor. + * + * accel G range | offset range + * --------------- | -------------- + * BNO055_ACCEL_RANGE_2G | +/-2000 + * BNO055_ACCEL_RANGE_4G | +/-4000 + * BNO055_ACCEL_RANGE_8G | +/-8000 + * BNO055_ACCEL_RANGE_16G | +/-16000 + * + * accel G range can be configured by using the + * bno055_set_accel_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_accel_offset( +struct bno055_accel_offset_t *accel_offset); +/*! + * @brief This API is used to write accel offset and accel radius + * offset form register 0x55 to 0x5A and radius form 0x67 and 0x68 + * + * @param accel_offset : The value of accel offset and radius + * + * bno055_accel_offset_t | result + * ------------------- | ---------------- + * x | accel offset x + * y | accel offset y + * z | accel offset z + * r | accel offset r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the accel offset varies based on + * the G-range of accel sensor. + * + * accel G range | offset range + * --------------- | -------------- + * BNO055_ACCEL_RANGE_2G | +/-2000 + * BNO055_ACCEL_RANGE_4G | +/-4000 + * BNO055_ACCEL_RANGE_8G | +/-8000 + * BNO055_ACCEL_RANGE_16G | +/-16000 + * + * accel G range can be configured by using the + * bno055_set_accel_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_accel_offset( +struct bno055_accel_offset_t *accel_offset); +/*****************************************************/ +/**\name FUNCTIONS FOR MAG OFFSET AND RADIUS*/ +/*****************************************************/ +/*! + * @brief This API is used to read mag offset + * offset form register 0x69 to 0x6A + * + * @param mag_offset : The value of mag offset and radius + * + * bno055_mag_offset_t | result + * ------------------- | ---------------- + * x | mag offset x + * y | mag offset y + * z | mag offset z + * r | mag radius r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the magnetometer offset is +/-6400 in LSB + */ + +BNO055_RETURN_FUNCTION_TYPE bno055_read_mag_offset( +struct bno055_mag_offset_t *mag_offset); +/*! + * @brief This API is used to read mag offset + * offset form register 0x69 to 0x6A + * + * @param mag_offset : The value of mag offset and radius + * + * bno055_mag_offset_t | result + * ------------------- | ---------------- + * x | mag offset x + * y | mag offset y + * z | mag offset z + * r | mag radius r + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the magnetometer offset is +/-6400 in LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_mag_offset( +struct bno055_mag_offset_t *mag_offset); +/*****************************************************/ +/**\name FUNCTIONS FOR GYRO OFFSET */ +/*****************************************************/ +/*! + * @brief This API is used to read gyro offset + * offset form register 0x61 to 0x66 + * + * @param gyro_offset : The value of gyro offset + * + * bno055_gyro_offset_t | result + * ------------------- | ---------------- + * x | gyro offset x + * y | gyro offset y + * z | gyro offset z + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the gyro offset varies based on + * the range of gyro sensor + * + * gyro G range | offset range + * -------------------- | ------------ + * BNO055_GYRO_RANGE_2000DPS | +/-32000 + * BNO055_GYRO_RANGE_1000DPS | +/-16000 + * BNO055_GYRO_RANGE_500DPS | +/-8000 + * BNO055_GYRO_RANGE_250DPS | +/-4000 + * BNO055_GYRO_RANGE_125DPS | +/-2000 + * + * Gyro range can be configured by using the + * bno055_set_gyro_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_read_gyro_offset( +struct bno055_gyro_offset_t *gyro_offset); +/*! + * @brief This API is used to read gyro offset + * offset form register 0x61 to 0x66 + * + * @param gyro_offset : The value of gyro offset + * + * bno055_gyro_offset_t | result + * ------------------- | ---------------- + * x | gyro offset x + * y | gyro offset y + * z | gyro offset z + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The range of the gyro offset varies based on + * the range of gyro sensor + * + * gyro G range | offset range + * -------------------- | ------------ + * BNO055_GYRO_RANGE_2000DPS | +/-32000 + * BNO055_GYRO_RANGE_1000DPS | +/-16000 + * BNO055_GYRO_RANGE_500DPS | +/-8000 + * BNO055_GYRO_RANGE_250DPS | +/-4000 + * BNO055_GYRO_RANGE_125DPS | +/-2000 + * + * Gyro range can be configured by using the + * bno055_set_gyro_range() API + */ +BNO055_RETURN_FUNCTION_TYPE bno055_write_gyro_offset( +struct bno055_gyro_offset_t *gyro_offset); +/********************************************************/ +/************** PAGE1 Functions *********************/ +/********************************************************/ +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL CONFIGURATION */ +/*****************************************************/ +/*! + * @brief This API used to read the accel range + * from page one register from 0x08 bit 0 and 1 + * + * @param accel_range_u8 : The value of accel range + * accel_range_u8 | result + * ----------------- | -------------- + * 0x00 | BNO055_ACCEL_RANGE_2G + * 0x01 | BNO055_ACCEL_RANGE_4G + * 0x02 | BNO055_ACCEL_RANGE_8G + * 0x03 | BNO055_ACCEL_RANGE_16G + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_range( +u8 *accel_range_u8); +/*! + * @brief This API used to write the accel range + * from page one register from 0x08 bit 0 and 1 + * + * @param accel_range_u8 : The value of accel range + * + * accel_range_u8 | result + * ----------------- | -------------- + * 0x00 | BNO055_ACCEL_RANGE_2G + * 0x01 | BNO055_ACCEL_RANGE_4G + * 0x02 | BNO055_ACCEL_RANGE_8G + * 0x03 | BNO055_ACCEL_RANGE_16G + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_range( +u8 accel_range_u8); +/*! + * @brief This API used to read the accel bandwidth + * from page one register from 0x08 bit 2 to 4 + * + * @param accel_bw_u8 : The value of accel bandwidth + * + * accel_bw_u8 | result + * ----------------- | --------------- + * 0x00 | BNO055_ACCEL_BW_7_81HZ + * 0x01 | BNO055_ACCEL_BW_15_63HZ + * 0x02 | BNO055_ACCEL_BW_31_25HZ + * 0x03 | BNO055_ACCEL_BW_62_5HZ + * 0x04 | BNO055_ACCEL_BW_125HZ + * 0x05 | BNO055_ACCEL_BW_250HZ + * 0x06 | BNO055_ACCEL_BW_500HZ + * 0x07 | BNO055_ACCEL_BW_1000HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_bw( +u8 *accel_bw_u8); +/*! + * @brief This API used to write the accel bandwidth + * from page one register from 0x08 bit 2 to 4 + * + * @param accel_bw_u8 : The value of accel bandwidth + * + * accel_bw_u8 | result + * ----------------- | --------------- + * 0x00 | BNO055_ACCEL_BW_7_81HZ + * 0x01 | BNO055_ACCEL_BW_15_63HZ + * 0x02 | BNO055_ACCEL_BW_31_25HZ + * 0x03 | BNO055_ACCEL_BW_62_5HZ + * 0x04 | BNO055_ACCEL_BW_125HZ + * 0x05 | BNO055_ACCEL_BW_250HZ + * 0x06 | BNO055_ACCEL_BW_500HZ + * 0x07 | BNO055_ACCEL_BW_1000HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_bw( +u8 accel_bw_u8); +/*! + * @brief This API used to read the accel power mode + * from page one register from 0x08 bit 5 to 7 + * + * @param accel_power_mode_u8 : The value of accel power mode + * accel_power_mode_u8 | result + * ----------------- | ------------- + * 0x00 | BNO055_ACCEL_NORMAL + * 0x01 | BNO055_ACCEL_SUSPEND + * 0x02 | BNO055_ACCEL_LOWPOWER_1 + * 0x03 | BNO055_ACCEL_STANDBY + * 0x04 | BNO055_ACCEL_LOWPOWER_2 + * 0x05 | BNO055_ACCEL_DEEPSUSPEND + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_power_mode( +u8 *accel_power_mode_u8); +/*! + * @brief This API used to write the accel power mode + * from page one register from 0x08 bit 5 to 7 + * + * @param accel_power_mode_u8 : The value of accel power mode + * accel_power_mode_u8 | result + * ----------------- | ------------- + * 0x00 | BNO055_ACCEL_NORMAL + * 0x01 | BNO055_ACCEL_SUSPEND + * 0x02 | BNO055_ACCEL_LOWPOWER_1 + * 0x03 | BNO055_ACCEL_STANDBY + * 0x04 | BNO055_ACCEL_LOWPOWER_2 + * 0x05 | BNO055_ACCEL_DEEPSUSPEND + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_power_mode( +u8 accel_power_mode_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR MAG CONFIGURATION */ +/*****************************************************/ +/*! + * @brief This API used to read the mag output data rate + * from page one register from 0x09 bit 0 to 2 + * + * @param mag_data_output_rate_u8 : The value of mag output data rate + * + * mag_data_output_rate_u8 | result + * ---------------------- |---------------------- + * 0x00 | MAG_DATA_OUTPUT_RATE_2HZ + * 0x01 | MAG_DATA_OUTPUT_RATE_6HZ + * 0x02 | MAG_DATA_OUTPUT_RATE_8HZ + * 0x03 | MAG_DATA_OUTPUT_RATE_10HZ + * 0x04 | MAG_DATA_OUTPUT_RATE_15HZ + * 0x05 | MAG_DATA_OUTPUT_RATE_20HZ + * 0x06 | MAG_DATA_OUTPUT_RATE_25HZ + * 0x07 | MAG_DATA_OUTPUT_RATE_30HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_data_output_rate( +u8 *mag_data_output_rate_u8); +/*! + * @brief This API used to write the mag output data rate + * from page one register from 0x09 bit 0 to 2 + * + * @param mag_data_output_rate_u8 : The value of mag output data rate + * + * mag_data_output_rate_u8 | result + * ---------------------- |---------------------- + * 0x00 | MAG_DATA_OUTPUT_RATE_2HZ + * 0x01 | MAG_DATA_OUTPUT_RATE_6HZ + * 0x02 | MAG_DATA_OUTPUT_RATE_8HZ + * 0x03 | MAG_DATA_OUTPUT_RATE_10HZ + * 0x04 | MAG_DATA_OUTPUT_RATE_15HZ + * 0x05 | MAG_DATA_OUTPUT_RATE_20HZ + * 0x06 | MAG_DATA_OUTPUT_RATE_25HZ + * 0x07 | MAG_DATA_OUTPUT_RATE_30HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_data_output_rate( +u8 mag_data_output_rate_u8); +/*! + * @brief This API used to read the mag operation mode + * from page one register from 0x09 bit 3 to 4 + * + * @param mag_operation_mode_u8 : The value of mag operation mode + * + * mag_operation_mode_u8 | result + * ------------------------|-------------------------- + * 0x00 | MAG_OPR_MODE_LOWPOWER + * 0x01 | MAG_OPR_MODE_REGULAR + * 0x02 | MAG_OPR_MODE_ENHANCED_REGULAR + * 0x03 | MAG_OPR_MODE_HIGH_ACCURACY + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_operation_mode( +u8 *mag_operation_mode_u8); +/*! + * @brief This API used to write the mag operation mode + * from page one register from 0x09 bit 3 to 4 + * + * @param mag_operation_mode_u8 : The value of mag operation mode + * + * mag_operation_mode_u8 | result + * ------------------------|-------------------------- + * 0x00 | MAG_OPR_MODE_LOWPOWER + * 0x01 | MAG_OPR_MODE_REGULAR + * 0x02 | MAG_OPR_MODE_ENHANCED_REGULAR + * 0x03 | MAG_OPR_MODE_HIGH_ACCURACY + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_operation_mode( +u8 mag_operation_mode_u8); +/*! + * @brief This API used to read the mag power mode + * from page one register from 0x09 bit 4 to 6 + * + * @param mag_power_mode_u8 : The value of mag power mode + * + * mag_power_mode_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_MAG_POWER_MODE_NORMAL + * 0x01 | BNO055_MAG_POWER_MODE_SLEEP + * 0x02 | BNO055_MAG_POWER_MODE_SUSPEND + * 0x03 | BNO055_MAG_POWER_MODE_FORCE_MODE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_power_mode( +u8 *mag_power_mode_u8); +/*! + * @brief This API used to write the mag power mode + * from page one register from 0x09 bit 4 to 6 + * + * @param mag_power_mode_u8 : The value of mag power mode + * + * mag_power_mode_u8 | result + * ------------------|----------------- + * 0x00 | BNO055_MAG_POWER_MODE_NORMAL + * 0x01 | BNO055_MAG_POWER_MODE_SLEEP + * 0x02 | BNO055_MAG_POWER_MODE_SUSPEND + * 0x03 | BNO055_MAG_POWER_MODE_FORCE_MODE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_power_mode( +u8 mag_power_mode_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR GYRO CONFIGURATION */ +/*****************************************************/ +/*! + * @brief This API used to read the gyro range + * from page one register from 0x0A bit 0 to 3 + * + * @param gyro_range_u8 : The value of gyro range + * + * gyro_range_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_RANGE_2000DPS + * 0x01 | BNO055_GYRO_RANGE_1000DPS + * 0x02 | BNO055_GYRO_RANGE_500DPS + * 0x03 | BNO055_GYRO_RANGE_250DPS + * 0x04 | BNO055_GYRO_RANGE_125DPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_range( +u8 *gyro_range_u8); +/*! + * @brief This API used to write the gyro range + * from page one register from 0x0A bit 0 to 3 + * + * @param gyro_range_u8 : The value of gyro range + * + * gyro_range_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_RANGE_2000DPS + * 0x01 | BNO055_GYRO_RANGE_1000DPS + * 0x02 | BNO055_GYRO_RANGE_500DPS + * 0x03 | BNO055_GYRO_RANGE_250DPS + * 0x04 | BNO055_GYRO_RANGE_125DPS + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_range( +u8 gyro_range_u8); +/*! + * @brief This API used to read the gyro bandwidth + * from page one register from 0x0A bit 3 to 5 + * + * @param gyro_bw_u8 : The value of gyro bandwidth + * + * gyro_bw_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_BW_523HZ + * 0x01 | BNO055_GYRO_BW_230HZ + * 0x02 | BNO055_GYRO_BW_116HZ + * 0x03 | BNO055_GYRO_BW_47HZ + * 0x04 | BNO055_GYRO_BW_23HZ + * 0x05 | BNO055_GYRO_BW_12HZ + * 0x06 | BNO055_GYRO_BW_64HZ + * 0x07 | BNO055_GYRO_BW_32HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_bw( +u8 *gyro_bw_u8); +/*! + * @brief This API used to write the gyro bandwidth + * from page one register from 0x0A bit 3 to 5 + * + * @param gyro_bw_u8 : The value of gyro bandwidth + * + * gyro_bw_u8 | result + * --------------------|----------------- + * 0x00 | BNO055_GYRO_BW_523HZ + * 0x01 | BNO055_GYRO_BW_230HZ + * 0x02 | BNO055_GYRO_BW_116HZ + * 0x03 | BNO055_GYRO_BW_47HZ + * 0x04 | BNO055_GYRO_BW_23HZ + * 0x05 | BNO055_GYRO_BW_12HZ + * 0x06 | BNO055_GYRO_BW_64HZ + * 0x07 | BNO055_GYRO_BW_32HZ + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_bw( +u8 gyro_bw_u8); +/*! + * @brief This API used to read the gyro power mode + * from page one register from 0x0B bit 0 to 2 + * + * @param gyro_power_mode_u8 : The value of gyro power mode + * + * gyro_power_mode_u8 | result + * ----------------------|---------------------------- + * 0x00 | GYRO_OPR_MODE_NORMAL + * 0x01 | GYRO_OPR_MODE_FASTPOWERUP + * 0x02 | GYRO_OPR_MODE_DEEPSUSPEND + * 0x03 | GYRO_OPR_MODE_SUSPEND + * 0x04 | GYRO_OPR_MODE_ADVANCE_POWERSAVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_power_mode( +u8 *gyro_power_mode_u8); +/*! + * @brief This API used to write the gyro power mode + * from page one register from 0x0B bit 0 to 2 + * + * @param gyro_power_mode_u8 : The value of gyro power mode + * + * gyro_power_mode_u8 | result + * ----------------------|---------------------------- + * 0x00 | GYRO_OPR_MODE_NORMAL + * 0x01 | GYRO_OPR_MODE_FASTPOWERUP + * 0x02 | GYRO_OPR_MODE_DEEPSUSPEND + * 0x03 | GYRO_OPR_MODE_SUSPEND + * 0x04 | GYRO_OPR_MODE_ADVANCE_POWERSAVE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_power_mode( +u8 gyro_power_mode_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL SLEEP SETTINGS */ +/*****************************************************/ +/*! + * @brief This API used to read the accel sleep mode + * from page one register from 0x0C bit 0 + * + * @param sleep_tmr_u8 : The value of accel sleep mode + * + * sleep_tmr_u8 | result + * ----------------- |------------------------------------ + * 0x00 | enable EventDrivenSampling(EDT) + * 0x01 | enable Equidistant sampling mode(EST) + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_sleep_tmr_mode( +u8 *sleep_tmr_u8); +/*! + * @brief This API used to write the accel sleep mode + * from page one register from 0x0C bit 0 + * + * @param sleep_tmr_u8 : The value of accel sleep mode + * + * sleep_tmr_u8 | result + * ----------------- |------------------------------------ + * 0x00 | enable EventDrivenSampling(EDT) + * 0x01 | enable Equidistant sampling mode(EST) + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_sleep_tmr_mode( +u8 sleep_tmr_u8); +/*! + * @brief This API used to read the accel sleep duration + * from page one register from 0x0C bit 1 to 4 + * + * @param sleep_durn_u8 : The value of accel sleep duration + * + * sleep_durn_u8 | result + * ---------------- |----------------------------- + * 0x05 | BNO055_ACCEL_SLEEP_DURN_0_5MS + * 0x06 | BNO055_ACCEL_SLEEP_DURN_1MS + * 0x07 | BNO055_ACCEL_SLEEP_DURN_2MS + * 0x08 | BNO055_ACCEL_SLEEP_DURN_4MS + * 0x09 | BNO055_ACCEL_SLEEP_DURN_6MS + * 0x0A | BNO055_ACCEL_SLEEP_DURN_10MS + * 0x0B | BNO055_ACCEL_SLEEP_DURN_25MS + * 0x0C | BNO055_ACCEL_SLEEP_DURN_50MS + * 0x0D | BNO055_ACCEL_SLEEP_DURN_100MS + * 0x0E | BNO055_ACCEL_SLEEP_DURN_500MS + * 0x0F | BNO055_ACCEL_SLEEP_DURN_1S + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_sleep_durn( +u8 *sleep_durn_u8); +/*! + * @brief This API used to write the accel sleep duration + * from page one register from 0x0C bit 1 to 4 + * + * @param sleep_durn_u8 : The value of accel sleep duration + * + * sleep_durn_u8 | result + * ---------------- |----------------------------- + * 0x05 | BNO055_ACCEL_SLEEP_DURN_0_5MS + * 0x06 | BNO055_ACCEL_SLEEP_DURN_1MS + * 0x07 | BNO055_ACCEL_SLEEP_DURN_2MS + * 0x08 | BNO055_ACCEL_SLEEP_DURN_4MS + * 0x09 | BNO055_ACCEL_SLEEP_DURN_6MS + * 0x0A | BNO055_ACCEL_SLEEP_DURN_10MS + * 0x0B | BNO055_ACCEL_SLEEP_DURN_25MS + * 0x0C | BNO055_ACCEL_SLEEP_DURN_50MS + * 0x0D | BNO055_ACCEL_SLEEP_DURN_100MS + * 0x0E | BNO055_ACCEL_SLEEP_DURN_500MS + * 0x0F | BNO055_ACCEL_SLEEP_DURN_1S + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_sleep_durn( +u8 sleep_durn_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR GYRO SLEEP SETTINGS */ +/*****************************************************/ +/*! + * @brief This API used to write the gyro sleep duration + * from page one register from 0x0D bit 0 to 2 + * + * @param sleep_durn_u8 : The value of gyro sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_sleep_durn( +u8 *sleep_durn_u8); +/*! + * @brief This API used to write the gyro sleep duration + * from page one register from 0x0D bit 0 to 2 + * + * @param sleep_durn_u8 : The value of gyro sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_sleep_durn( +u8 sleep_durn); +/*! + * @brief This API used to read the gyro auto sleep duration + * from page one register from 0x0D bit 3 to 5 + * + * @param auto_sleep_durn_u8 : The value of gyro auto sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_auto_sleep_durn( +u8 *auto_sleep_durn_u8); +/*! + * @brief This API used to write the gyro auto sleep duration + * from page one register from 0x0D bit 3 to 5 + * + * @param auto_sleep_durn_u8 : The value of gyro auto sleep duration + * @param bw : The value of gyro bandwidth + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_gyro_set_auto_sleep_durn( +u8 auto_sleep_durn_u8, u8 bw); +/*****************************************************/ +/**\name FUNCTIONS FOR MAG SLEEP SETTINGS */ +/*****************************************************/ +/*! + * @brief This API used to read the mag sleep mode + * from page one register from 0x0E bit 0 + * + * @param sleep_mode_u8 : The value of mag sleep mode + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_sleep_mode( +u8 *sleep_mode_u8); +/*! + * @brief This API used to write the mag sleep mode + * from page one register from 0x0E bit 0 + * + * @param sleep_mode_u8 : The value of mag sleep mode + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_sleep_mode( +u8 sleep_mode_u8); +/*! + * @brief This API used to read the mag sleep duration + * from page one register from 0x0E bit 1 to 4 + * + * @param sleep_durn_u8 : The value of mag sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_mag_sleep_durn( +u8 *sleep_durn_u8); +/*! + * @brief This API used to write the mag sleep duration + * from page one register from 0x0E bit 1 to 4 + * + * @param sleep_durn_u8 : The value of mag sleep duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_mag_sleep_durn( +u8 sleep_durn_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR GYRO INTERRUPT MASK */ +/*****************************************************/ +/*! + * @brief This API used to read the gyro anymotion interrupt mask + * from page one register from 0x0F bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt mask + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_gyro_any_motion( +u8 *gyro_any_motion_u8); +/*! + * @brief This API used to write the gyro anymotion interrupt mask + * from page one register from 0x0F bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt mask + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_gyro_any_motion( +u8 gyro_any_motion_u8); +/*! + * @brief This API used to read the gyro highrate interrupt mask + * from page one register from 0x0F bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt mask + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_gyro_highrate( +u8 *gyro_highrate_u8); +/*! + * @brief This API used to write the gyro highrate interrupt mask + * from page one register from 0x0F bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt mask + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_gyro_highrate( +u8 gyro_highrate_u8); +/*****************************************************/ +/**\name APIs FOR ACCEL INTERRUPT MASK */ +/*****************************************************/ +/*! + * @brief This API used to read the accel highg interrupt mask + * from page one register from 0x0F bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt mask + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_high_g( +u8 *accel_high_g_u8); +/*! + * @brief This API used to write the accel highg interrupt mask + * from page one register from 0x0F bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt mask + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_high_g( +u8 accel_high_g_u8); +/*! + * @brief This API used to read the accel anymotion interrupt mask + * from page one register from 0x0F bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt mask + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_any_motion( +u8 *accel_any_motion_u8); +/*! + * @brief This API used to write the accel anymotion interrupt mask + * from page one register from 0x0F bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt mask + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_any_motion( +u8 accel_any_motion_u8); +/*! + * @brief This API used to read the accel nomotion interrupt mask + * from page one register from 0x0F bit 7 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt mask + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres()) + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_mask_accel_no_motion( +u8 *accel_nomotion_u8); +/*! + * @brief This API used to write the accel nomotion interrupt mask + * from page one register from 0x0F bit 7 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt mask + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_mask_accel_no_motion( +u8 accel_nomotion_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR GYRO INTERRUPT */ +/*****************************************************/ +/*! + * @brief This API used to read the gyro anymotion interrupt + * from page one register from 0x10 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_gyro_any_motion( +u8 *gyro_any_motion_u8); +/*! + * @brief This API used to write the gyro anymotion interrupt + * from page one register from 0x10 bit 2 + * + * @param gyro_any_motion_u8 : The value of gyro anymotion interrupt + * gyro_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro anymotion interrupt + * configure the following settings + * + * Axis: + * bno055_set_gyro_any_motion_axis_enable() + * + * Filter setting: + * bno055_set_gyro_any_motion_filter() + * + * Threshold : + * + * bno055_set_gyro_any_motion_thres() + * + * Slope samples : + * + * bno055_set_gyro_any_motion_slope_samples() + * + * Awake duration : + * + * bno055_set_gyro_any_motion_awake_durn() + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_gyro_any_motion( +u8 gyro_any_motion_u8); +/*! + * @brief This API used to read the gyro highrate interrupt + * from page one register from 0x10 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_gyro_highrate( +u8 *gyro_highrate_u8); +/*! + * @brief This API used to write the gyro highrate interrupt + * from page one register from 0x10 bit 3 + * + * @param gyro_highrate_u8 : The value of gyro highrate interrupt + * gyro_highrate_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the gyro highrate interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_gyro_highrate_axis_enable() + * + * Filter : + * + * bno055_set_gyro_highrate_filter() + * + * Threshold : + * + * bno055_get_gyro_highrate_x_thres() + * + * bno055_get_gyro_highrate_y_thres() + * + * bno055_get_gyro_highrate_z_thres() + * + * Hysteresis : + * + * bno055_set_gyro_highrate_x_hyst() + * + * bno055_set_gyro_highrate_y_hyst() + * + * bno055_set_gyro_highrate_z_hyst() + * + * Duration : + * + * bno055_set_gyro_highrate_x_durn() + * + * bno055_set_gyro_highrate_y_durn() + * + * bno055_set_gyro_highrate_z_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_gyro_highrate( +u8 gyro_highrate_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL INTERRUPT */ +/*****************************************************/ +/*! + * @brief This API used to read the accel highg interrupt + * from page one register from 0x10 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_high_g( +u8 *accel_high_g_u8); +/*! + * @brief This API used to write the accel highg interrupt + * from page one register from 0x10 bit 5 + * + * @param accel_high_g_u8 : The value of accel highg interrupt + * accel_high_g_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel highg interrupt + * configure the below settings by using + * the following APIs + * + * Axis : + * + * bno055_set_accel_high_g_axis_enable() + * + * Threshold : + * + * bno055_set_accel_high_g_thres() + * + * Duration : + * + * bno055_set_accel_high_g_durn() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_high_g( +u8 accel_high_g_u8); +/*! + * @brief This API used to read the accel anymotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_any_motion( +u8 *accel_any_motion_u8); +/*! + * @brief This API used to write the accel anymotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_any_motion_u8 : The value of accel anymotion interrupt + * accel_any_motion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel anymotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Duration: + * + * bno055_set_accel_any_motion_durn() + * + * Threshold: + * + * bno055_set_accel_any_motion_thres() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_any_motion( +u8 accel_any_motion_u8); +/*! + * @brief This API used to read the accel nomotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_intr_accel_no_motion( +u8 *accel_nomotion_u8); +/*! + * @brief This API used to write the accel nomotion interrupt + * from page one register from 0x10 bit 6 + * + * @param accel_nomotion_u8 : The value of accel nomotion interrupt + * accel_nomotion_u8 | result + * -------------------- |------------ + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note While enabling the accel nomotion interrupt + * configure the following settings + * + * Axis: + * + * bno055_set_accel_any_motion_no_motion_axis_enable() + * + * Threshold : + * + * bno055_set_accel_slow_no_motion_thres() + * + * Duration : + * + * bno055_set_accel_slow_no_motion_durn() + * + * Slow/no motion enable: + * + * bno055_set_accel_slow_no_motion_enable() + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_intr_accel_no_motion( +u8 accel_nomotion_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL ANY_MOTION THRESHOLD */ +/*****************************************************/ +/*! + * @brief This API used to read the accel any motion threshold + * from page one register from 0x11 bit 0 to 7 + * + * @param accel_any_motion_thres_u8 : The value of any motion threshold + * accel_any_motion_thres_u8 | result + * ------------------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion threshold dependent on the + * range values + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_thres( +u8 *accel_any_motion_thres_u8); +/*! + * @brief This API used to write the accel any motion threshold + * from page one register from 0x11 bit 0 to 7 + * + * @param accel_any_motion_thres_u8 : The value of any motion threshold + * accel_any_motion_thres_u8 | result + * ------------------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel anymotion threshold dependent on the + * range values + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_thres( +u8 accel_any_motion_thres_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL ANY_MOTION DURATION */ +/*****************************************************/ +/*! + * @brief This API used to read the accel anymotion duration + * from page one register from 0x12 bit 0 to 1 + * + * @param accel_any_motion_durn_u8 : The value of accel anymotion duration + * accel_any_motion_durn_u8 | result + * ------------------------- | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_durn( +u8 *accel_any_motion_durn_u8); +/*! + * @brief This API used to write the accel anymotion duration + * from page one register from 0x12 bit 0 to 1 + * + * @param accel_any_motion_durn_u8 : The value of accel anymotion duration + * + * accel_any_motion_durn_u8 | result + * ------------------------- | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_durn( +u8 accel_any_motion_durn_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL ANY_MOTION AXIS ENABLE */ +/*****************************************************/ +/*! + * @brief This API used to read the accel anymotion enable + * from page one register from 0x12 bit 2 to 4 + * + * @param data_u8 : The value of accel anymotion enable + * data_u8 | result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel anymotion axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS | 0 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 1 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_any_motion_no_motion_axis_enable( +u8 channel_u8, u8 *data_u8); +/*! + * @brief This API used to write the accel anymotion enable + * from page one register from 0x12 bit 2 to 4 + * + * @param data_u8 : The value of accel anymotion enable + * data_u8 | result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel anymotion axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS | 0 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 1 + * BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_any_motion_no_motion_axis_enable( +u8 channel_u8, u8 data_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL HIGHG AXIS ENABLE */ +/*****************************************************/ +/*! + * @brief This API used to read the accel highg enable + * from page one register from 0x12 bit 5 to 7 + * + * @param data_u8 : The value of accel highg enable + * data_u8| result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel highg axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_HIGH_G_X_AXIS | 0 + * BNO055_ACCEL_HIGH_G_Y_AXIS | 1 + * BNO055_ACCEL_HIGH_G_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_axis_enable( +u8 channel_u8, u8 *data_u8); +/*! + * @brief This API used to write the accel highg enable + * from page one register from 0x12 bit 5 to 7 + * + * @param data_u8 : The value of accel highg enable + * data_u8| result + * ------------ | ------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of accel highg axis selection + * channel_u8 | value + * -------------------------- | ---------- + * BNO055_ACCEL_HIGH_G_X_AXIS | 0 + * BNO055_ACCEL_HIGH_G_Y_AXIS | 1 + * BNO055_ACCEL_HIGH_G_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_axis_enable( +u8 channel_u8, u8 data_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL HIGHG DURATION */ +/*****************************************************/ +/*! + * @brief This API used to read the accel highg duration + * from page one register from 0x13 bit 0 to 7 + * + * @param accel_high_g_durn_u8 : The value of accel highg duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The high-g interrupt trigger delay according + * to [highg duration + 1] * 2 ms + * + * in a range from 2 ms to 512 ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_durn( +u8 *accel_high_g_durn_u8); +/*! + * @brief This API used to write the accel highg duration + * from page one register from 0x13 bit 0 to 7 + * + * @param accel_high_g_durn_u8 : The value of accel highg duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note The high-g interrupt trigger delay according + * to [highg duration + 1] * 2 ms + * + * in a range from 2 ms to 512 ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_durn( +u8 accel_high_g_durn_u8); +/*****************************************************/ +/**\name FUNCTIONS FOR ACCEL HIGHG THRESHOLD */ +/*****************************************************/ +/*! + * @brief This API used to read the accel highg threshold + * from page one register from 0x14 bit 0 to 7 + * + * @param accel_high_g_thres_u8 : The value of accel highg threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 7.81mg | 1LSB + * 4g | 15.63mg | 1LSB + * 8g | 31.25mg | 1LSB + * 16g | 62.5mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_high_g_thres( +u8 *accel_high_g_thres_u8); +/*! + * @brief This API used to write the accel highg threshold + * from page one register from 0x14 bit 0 to 7 + * + * @param accel_high_g_thres_u8 : The value of accel highg threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel highg interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 7.81mg | 1LSB + * 4g | 15.63mg | 1LSB + * 8g | 31.25mg | 1LSB + * 16g | 62.5mg | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_high_g_thres( +u8 accel_high_g_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR ACCEL SLOWNOMOTION THRESHOLD */ +/**************************************************************/ +/*! + * @brief This API used to read the accel slownomotion threshold + * from page one register from 0x15 bit 0 to 7 + * + * @param accel_slow_no_motion_thres_u8 : + * The value of accel slownomotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel slow no motion interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_thres( +u8 *accel_slow_no_motion_thres_u8); +/*! + * @brief This API used to write the accel slownomotion threshold + * from page one register from 0x15 bit 0 to 7 + * + * @param accel_slow_no_motion_thres_u8 : + * The value of accel slownomotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Accel slow no motion interrupt threshold dependent + * for accel g range + * + * accel_range_u8 | threshold | LSB + * ------------- | ------------- | --------- + * 2g | 3.19mg | 1LSB + * 4g | 7.81mg | 1LSB + * 8g | 15.63mg | 1LSB + * 16g | 31.25mg | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_thres( +u8 accel_slow_no_motion_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR ACCEL SLOWNOMOTION ENABLE */ +/**************************************************************/ +/*! + * @brief This API used to read accel slownomotion enable + * from page one register from 0x16 bit 0 + * + * @param accel_slow_no_motion_en_u8 : The value of accel slownomotion enable + * accel_slow_no_motion_en_u8 | result + * ------------------------ | -------- + * 0x01 | Slow motion + * 0x00 | No motion + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_enable( +u8 *accel_slow_no_motion_en_u8); +/*! + * @brief This API used to write accel slownomotion enable + * from page one register from 0x16 bit 0 + * + * @param accel_slow_no_motion_en_u8 : The value of accel slownomotion enable + * accel_slow_no_motion_en_u8 | result + * ------------------------ | -------- + * 0x01 | Slow motion + * 0x00 | No motion + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_enable( +u8 accel_slow_no_motion_en_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR ACCEL SLOWNOMOTION DURATION */ +/**************************************************************/ +/*! + * @brief This API used to read accel slownomotion duration + * from page one register from 0x16 bit 1 to 6 + * + * @param accel_slow_no_motion_durn_u8 : + * The value of accel slownomotion duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_accel_slow_no_motion_durn( +u8 *accel_slow_no_motion_durn_u8); +/*! + * @brief This API used to write accel slownomotion duration + * from page one register from 0x16 bit 1 to 6 + * + * @param accel_slow_no_motion_durn_u8 : + * The value of accel slownomotion duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_accel_slow_no_motion_durn( +u8 accel_slow_no_motion_durn_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO ANY_MOTION AXIS ENABLE */ +/**************************************************************/ +/*! + * @brief This API used to read the gyro anymotion enable + * from page one register from 0x17 bit 0 to 2 + * + * @param data_u8 : The value of gyro anymotion enable + * data_u8 | result + * ----------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro anymotion axis selection + * channel_u8 | value + * --------------------------- | ---------- + * BNO055_GYRO_ANY_MOTIONX_AXIS | 0 + * BNO055_GYRO_ANY_MOTIONY_AXIS | 1 + * BNO055_GYRO_ANY_MOTIONZ_AXIS | 2 + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_axis_enable( +u8 channel_u8, u8 *data_u8); +/*! + * @brief This API used to write the gyro anymotion enable + * from page one register from 0x17 bit 0 to 2 + * + * @param data_u8 : The value of gyro anymotion enable + * data_u8 | result + * ----------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro anymotion axis selection + * channel_u8 | value + * --------------------------- | ---------- + * BNO055_GYRO_ANY_MOTIONX_AXIS | 0 + * BNO055_GYRO_ANY_MOTIONY_AXIS | 1 + * BNO055_GYRO_ANY_MOTIONZ_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_axis_enable( +u8 channel_u8, u8 data_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE ENABLE */ +/**************************************************************/ +/*! + * @brief This API used to read the gyro highrate enable + * from page one register from 0x17 bit 3 to 5 + * + * @param data_u8 : The value of gyro highrate enable + * data_u8 | result + * ---------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro highrate axis selection + * channel_u8 | value + * ------------------------ | ---------- + * BNO055_GYRO_HIGHRATE_X_AXIS | 0 + * BNO055_GYRO_HIGHRATE_Y_AXIS | 1 + * BNO055_GYRO_HIGHRATE_Z_AXIS | 2 + * + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_axis_enable( +u8 channel_u8, u8 *data_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE AXIS ENABLE */ +/**************************************************************/ +/*! + * @brief This API used to write the gyro highrate enable + * from page one register from 0x17 bit 3 to 5 + * + * @param data_u8 : The value of gyro highrate enable + * data_u8 | result + * ---------------- |------------- + * 0x01 | BNO055_BIT_ENABLE + * 0x00 | BNO055_BIT_DISABLE + * @param channel_u8 : The value of gyro highrate axis selection + * channel_u8 | value + * ------------------------ | ---------- + * BNO055_GYRO_HIGHRATE_X_AXIS | 0 + * BNO055_GYRO_HIGHRATE_Y_AXIS | 1 + * BNO055_GYRO_HIGHRATE_Z_AXIS | 2 + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_axis_enable( +u8 channel_u8, u8 data_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO ANY_MOTION FILTER */ +/**************************************************************/ +/*! + * @brief This API used to read gyro anymotion filter + * from page one register from 0x17 bit 6 + * + * @param gyro_any_motion_filter_u8 : The value of gyro anymotion filter + * gyro_any_motion_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_filter( +u8 *gyro_any_motion_filter_u8); +/*! + * @brief This API used to write gyro anymotion filter + * from page one register from 0x17 bit 6 + * + * @param gyro_any_motion_filter_u8 : The value of gyro anymotion filter + * gyro_any_motion_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_filter( +u8 gyro_any_motion_filter_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE FILTER */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate filter + * from page one register from 0x17 bit 7 + * + * @param gyro_highrate_filter_u8 : The value of gyro highrate filter + * gyro_highrate_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_filter( +u8 *gyro_highrate_filter_u8); +/*! + * @brief This API used to write gyro highrate filter + * from page one register from 0x17 bit 7 + * + * @param gyro_highrate_filter_u8 : The value of gyro highrate filter + * gyro_highrate_filter_u8 | result + * --------------------------- |------------ + * 0x00 | BNO055_GYRO_FILTERED_CONFIG + * 0x01 | BNO055_GYRO_UNFILTERED_CONFIG + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_filter( +u8 gyro_highrate_filter_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE X THRESHOLD */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate x threshold + * from page one register from 0x18 bit 0 to 4 + * + * @param gyro_highrate_x_thres_u8 : The value of gyro x highrate threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_thres( +u8 *gyro_highrate_x_thres_u8); +/*! + * @brief This API used to write gyro highrate x threshold + * from page one register from 0x18 bit 0 to 4 + * + * @param gyro_highrate_x_thres_u8 : The value of gyro x highrate threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_thres( +u8 gyro_highrate_x_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE X HYSTERESIS */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate x hysteresis + * from page one register from 0x18 bit 5 to 6 + * + * @param gyro_highrate_x_hyst_u8 : The value of gyro highrate x hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_x_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_hyst( +u8 *gyro_highrate_x_hyst_u8); +/*! + * @brief This API used to write gyro highrate x hysteresis + * from page one register from 0x18 bit 5 to 6 + * + * @param gyro_highrate_x_hyst_u8 : The value of gyro highrate x hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_x_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_hyst( +u8 gyro_highrate_x_hyst_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE X DURATION */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate x duration + * from page one register from 0x19 bit 0 to 7 + * + * @param gyro_highrate_x_durn_u8 : The value of gyro highrate x duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_x_durn_u8)*2.5ms + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_x_durn( +u8 *gyro_highrate_x_durn_u8); +/*! + * @brief This API used to write gyro highrate x duration + * from page one register from 0x19 bit 0 to 7 + * + * @param gyro_highrate_x_durn_u8 : The value of gyro highrate x duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_x_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_x_durn( +u8 gyro_highrate_x_durn_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Y THRESHOLD */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate y threshold + * from page one register from 0x1A bit 0 to 4 + * + * @param gyro_highrate_y_thres_u8 : The value of gyro highrate y threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_thres( +u8 *gyro_highrate_y_thres_u8); +/*! + * @brief This API used to write gyro highrate y threshold + * from page one register from 0x1A bit 0 to 4 + * + * @param gyro_highrate_y_thres_u8 : The value of gyro highrate y threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_thres( +u8 gyro_highrate_y_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Y HYSTERESIS */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate y hysteresis + * from page one register from 0x1A bit 5 to 6 + * + * @param gyro_highrate_y_hyst_u8 : The value of gyro highrate y hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_y_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_hyst( +u8 *gyro_highrate_y_hyst_u8); +/*! + * @brief This API used to write gyro highrate y hysteresis + * from page one register from 0x1A bit 5 to 6 + * + * @param gyro_highrate_y_hyst_u8 : The value of gyro highrate y hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_y_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_hyst( +u8 gyro_highrate_y_hyst_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Y DURATION */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate y duration + * from page one register from 0x1B bit 0 to 7 + * + * @param gyro_highrate_y_durn_u8 : The value of gyro highrate y duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_y_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_y_durn( +u8 *gyro_highrate_y_durn_u8); +/*! + * @brief This API used to write gyro highrate y duration + * from page one register from 0x1B bit 0 to 7 + * + * @param gyro_highrate_y_durn_u8 : The value of gyro highrate y duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_y_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_y_durn( +u8 gyro_highrate_y_durn_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Z THRESHOLD */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate z threshold + * from page one register from 0x1C bit 0 to 4 + * + * @param gyro_highrate_z_thres_u8 : The value of gyro highrate z threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_thres( +u8 *gyro_highrate_z_thres_u8); +/*! + * @brief This API used to write gyro highrate z threshold + * from page one register from 0x1C bit 0 to 4 + * + * @param gyro_highrate_z_thres_u8 : The value of gyro highrate z threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate threshold dependent on the + * selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.5dps | 1LSB + * 1000 | 31.25dps | 1LSB + * 500 | 15.625dps | 1LSB + * 125 | 7.8125dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_thres( +u8 gyro_highrate_z_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Z HYSTERESIS */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate z hysteresis + * from page one register from 0x1C bit 5 to 6 + * + * @param gyro_highrate_z_hyst_u8 : The value of gyro highrate z hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_z_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_hyst( +u8 *gyro_highrate_z_hyst_u8); +/*! + * @brief This API used to write gyro highrate z hysteresis + * from page one register from 0x1C bit 5 to 6 + * + * @param gyro_highrate_z_hyst_u8 : The value of gyro highrate z hysteresis + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro high rate hysteresis calculated by + * + * using this (255 + 256 * gyro_highrate_z_hyst_u8) *4 LSB + * + * The high rate value scales with the range setting + * + * gyro_range_u8 | hysteresis | LSB + * ----------------- | ------------- | --------- + * 2000 | 62.26dps | 1LSB + * 1000 | 31.13dps | 1LSB + * 500 | 15.56dps | 1LSB + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_hyst( +u8 gyro_highrate_z_hyst_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO HIGHRATE Z DURATION */ +/**************************************************************/ +/*! + * @brief This API used to read gyro highrate z duration + * from page one register from 0x1D bit 0 to 7 + * + * @param gyro_highrate_z_durn_u8 : The value of gyro highrate z duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_z_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_highrate_z_durn( +u8 *gyro_highrate_z_durn_u8); +/*! + * @brief This API used to write gyro highrate z duration + * from page one register from 0x1D bit 0 to 7 + * + * @param gyro_highrate_z_durn_u8 : The value of gyro highrate z duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro highrate duration calculate by using the formula + * + * (1 + gyro_highrate_z_durn_u8)*2.5ms + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_highrate_z_durn( +u8 gyro_highrate_z_durn_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO ANY_MOTION THRESHOLD */ +/**************************************************************/ +/*! + * @brief This API used to read gyro anymotion threshold + * from page one register from 0x1E bit 0 to 6 + * + * @param gyro_any_motion_thres_u8 : The value of gyro anymotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt threshold dependent + * on the selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 1dps | 1LSB + * 1000 | 0.5dps | 1LSB + * 500 | 0.25dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_thres( +u8 *gyro_any_motion_thres_u8); +/*! + * @brief This API used to write gyro anymotion threshold + * from page one register from 0x1E bit 0 to 6 + * + * @param gyro_any_motion_thres_u8 : The value of gyro anymotion threshold + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + * @note Gyro anymotion interrupt threshold dependent + * on the selection of gyro range + * + * gyro_range_u8 | threshold | LSB + * ----------------- | ------------- | --------- + * 2000 | 1dps | 1LSB + * 1000 | 0.5dps | 1LSB + * 500 | 0.25dps | 1LSB + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_thres( +u8 gyro_any_motion_thres_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO ANY_MOTION SLOPE SAMPLES */ +/**************************************************************/ +/*! + * @brief This API used to read gyro anymotion slope samples + * from page one register from 0x1F bit 0 to 1 + * + * @param gyro_any_motion_slope_samples_u8 : + * The value of gyro anymotion slope samples + * gyro_any_motion_slope_samples_u8 | result + * ---------------------------------- | ----------- + * 0 | 8 samples + * 1 | 16 samples + * 2 | 32 samples + * 3 | 64 samples + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_slope_samples( +u8 *gyro_any_motion_slope_samples_u8); +/*! + * @brief This API used to write gyro anymotion slope samples + * from page one register from 0x1F bit 0 to 1 + * + * @param gyro_any_motion_slope_samples_u8 : + * The value of gyro anymotion slope samples + * gyro_any_motion_slope_samples_u8 | result + * ---------------------------------- | ----------- + * 0 | 8 samples + * 1 | 16 samples + * 2 | 32 samples + * 3 | 64 samples + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_slope_samples( +u8 gyro_any_motion_slope_samples_u8); +/**************************************************************/ +/**\name FUNCTIONS FOR GYRO ANY_MOTION AWAKE DURATION */ +/**************************************************************/ +/*! + * @brief This API used to read gyro anymotion awake duration + * from page one register from 0x1F bit 2 to 3 + * + * @param gyro_awake_durn_u8 : The value of gyro anymotion awake duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_get_gyro_any_motion_awake_durn( +u8 *gyro_awake_durn_u8); +/*! + * @brief This API used to write gyro anymotion awake duration + * from page one register from 0x1F bit 2 to 3 + * + * @param gyro_awake_durn_u8 : The value of gyro anymotion awake duration + * + * @return results of bus communication function + * @retval 0 -> BNO055_SUCCESS + * @retval 1 -> BNO055_ERROR + * + */ +BNO055_RETURN_FUNCTION_TYPE bno055_set_gyro_any_motion_awake_durn( +u8 gyro_awake_durn_u8); +#endif diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055_support.c b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055_support.c new file mode 100644 index 0000000000..e80841827b --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/bosch-driver/bno055_support.c @@ -0,0 +1,582 @@ +/* +**************************************************************************** +* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH +* +* bno055_support.c +* Date: 2016/03/14 +* Revision: 1.0.4 $ +* +* Usage: Sensor Driver support file for BNO055 sensor +* +**************************************************************************** +* License: +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the distribution. +* +* Neither the name of the copyright holder nor the names of the +* contributors may be used to endorse or promote products derived from +* this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND +* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR +* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER +* OR CONTRIBUTORS BE LIABLE FOR ANY +* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, +* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, +* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) +* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE +* +* The information provided is believed to be accurate and reliable. +* The copyright holder assumes no responsibility +* for the consequences of use +* of such information nor for any infringement of patents or +* other rights of third parties which may result from its use. +* No license is granted by implication or otherwise under any patent or +* patent rights of the copyright holder. +**************************************************************************/ +/*---------------------------------------------------------------------------* + Includes +*---------------------------------------------------------------------------*/ +#include "bno055.h" + +/*----------------------------------------------------------------------------* + * The following APIs are used for reading and writing of + * sensor data using I2C communication +*----------------------------------------------------------------------------*/ +#ifdef BNO055_API +#define BNO055_I2C_BUS_WRITE_ARRAY_INDEX ((u8)1) +/* \Brief: The API is used as I2C bus read + * \Return : Status of the I2C read + * \param dev_addr : The device address of the sensor + * \param reg_addr : Address of the first register, + * will data is going to be read + * \param reg_data : This data read from the sensor, + * which is hold in an array + * \param cnt : The no of byte of data to be read + */ +s8 BNO055_I2C_bus_read(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt); +/* \Brief: The API is used as SPI bus write + * \Return : Status of the SPI write + * \param dev_addr : The device address of the sensor + * \param reg_addr : Address of the first register, + * will data is going to be written + * \param reg_data : It is a value hold in the array, + * will be used for write the value into the register + * \param cnt : The no of byte of data to be write + */ +s8 BNO055_I2C_bus_write(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt); +/* + * \Brief: I2C init routine +*/ +s8 I2C_routine(void); +#endif +/********************End of I2C APIs declarations***********************/ +/* Brief : The delay routine + * \param : delay in ms +*/ +void BNO055_delay_msek(u32 msek); +/* This API is an example for reading sensor data + * \param: None + * \return: communication result + */ +s32 bno055_data_readout_template(void); +/*----------------------------------------------------------------------------* + * struct bno055_t parameters can be accessed by using BNO055 + * BNO055_t having the following parameters + * Bus write function pointer: BNO055_WR_FUNC_PTR + * Bus read function pointer: BNO055_RD_FUNC_PTR + * Burst read function pointer: BNO055_BRD_FUNC_PTR + * Delay function pointer: delay_msec + * I2C address: dev_addr + * Chip id of the sensor: chip_id +*---------------------------------------------------------------------------*/ +struct bno055_t bno055; +/* This API is an example for reading sensor data + * \param: None + * \return: communication result + */ +s32 bno055_data_readout_template(void) +{ + /* Variable used to return value of + communication routine*/ + s32 comres = BNO055_ERROR; + /* variable used to set the power mode of the sensor*/ + u8 power_mode = BNO055_INIT_VALUE; + /*********read raw accel data***********/ + /* variable used to read the accel x data */ + s16 accel_datax = BNO055_INIT_VALUE; + /* variable used to read the accel y data */ + s16 accel_datay = BNO055_INIT_VALUE; + /* variable used to read the accel z data */ + s16 accel_dataz = BNO055_INIT_VALUE; + /* variable used to read the accel xyz data */ + struct bno055_accel_t accel_xyz; + + /*********read raw mag data***********/ + /* variable used to read the mag x data */ + s16 mag_datax = BNO055_INIT_VALUE; + /* variable used to read the mag y data */ + s16 mag_datay = BNO055_INIT_VALUE; + /* variable used to read the mag z data */ + s16 mag_dataz = BNO055_INIT_VALUE; + /* structure used to read the mag xyz data */ + struct bno055_mag_t mag_xyz; + + /***********read raw gyro data***********/ + /* variable used to read the gyro x data */ + s16 gyro_datax = BNO055_INIT_VALUE; + /* variable used to read the gyro y data */ + s16 gyro_datay = BNO055_INIT_VALUE; + /* variable used to read the gyro z data */ + s16 gyro_dataz = BNO055_INIT_VALUE; + /* structure used to read the gyro xyz data */ + struct bno055_gyro_t gyro_xyz; + + /*************read raw Euler data************/ + /* variable used to read the euler h data */ + s16 euler_data_h = BNO055_INIT_VALUE; + /* variable used to read the euler r data */ + s16 euler_data_r = BNO055_INIT_VALUE; + /* variable used to read the euler p data */ + s16 euler_data_p = BNO055_INIT_VALUE; + /* structure used to read the euler hrp data */ + struct bno055_euler_t euler_hrp; + + /************read raw quaternion data**************/ + /* variable used to read the quaternion w data */ + s16 quaternion_data_w = BNO055_INIT_VALUE; + /* variable used to read the quaternion x data */ + s16 quaternion_data_x = BNO055_INIT_VALUE; + /* variable used to read the quaternion y data */ + s16 quaternion_data_y = BNO055_INIT_VALUE; + /* variable used to read the quaternion z data */ + s16 quaternion_data_z = BNO055_INIT_VALUE; + /* structure used to read the quaternion wxyz data */ + struct bno055_quaternion_t quaternion_wxyz; + + /************read raw linear acceleration data***********/ + /* variable used to read the linear accel x data */ + s16 linear_accel_data_x = BNO055_INIT_VALUE; + /* variable used to read the linear accel y data */ + s16 linear_accel_data_y = BNO055_INIT_VALUE; + /* variable used to read the linear accel z data */ + s16 linear_accel_data_z = BNO055_INIT_VALUE; + /* structure used to read the linear accel xyz data */ + struct bno055_linear_accel_t linear_acce_xyz; + + /*****************read raw gravity sensor data****************/ + /* variable used to read the gravity x data */ + s16 gravity_data_x = BNO055_INIT_VALUE; + /* variable used to read the gravity y data */ + s16 gravity_data_y = BNO055_INIT_VALUE; + /* variable used to read the gravity z data */ + s16 gravity_data_z = BNO055_INIT_VALUE; + /* structure used to read the gravity xyz data */ + struct bno055_gravity_t gravity_xyz; + + /*************read accel converted data***************/ + /* variable used to read the accel x data output as m/s2 or mg */ + double d_accel_datax = BNO055_INIT_VALUE; + /* variable used to read the accel y data output as m/s2 or mg */ + double d_accel_datay = BNO055_INIT_VALUE; + /* variable used to read the accel z data output as m/s2 or mg */ + double d_accel_dataz = BNO055_INIT_VALUE; + /* structure used to read the accel xyz data output as m/s2 or mg */ + struct bno055_accel_double_t d_accel_xyz; + + /******************read mag converted data********************/ + /* variable used to read the mag x data output as uT*/ + double d_mag_datax = BNO055_INIT_VALUE; + /* variable used to read the mag y data output as uT*/ + double d_mag_datay = BNO055_INIT_VALUE; + /* variable used to read the mag z data output as uT*/ + double d_mag_dataz = BNO055_INIT_VALUE; + /* structure used to read the mag xyz data output as uT*/ + struct bno055_mag_double_t d_mag_xyz; + + /*****************read gyro converted data************************/ + /* variable used to read the gyro x data output as dps or rps */ + double d_gyro_datax = BNO055_INIT_VALUE; + /* variable used to read the gyro y data output as dps or rps */ + double d_gyro_datay = BNO055_INIT_VALUE; + /* variable used to read the gyro z data output as dps or rps */ + double d_gyro_dataz = BNO055_INIT_VALUE; + /* structure used to read the gyro xyz data output as dps or rps */ + struct bno055_gyro_double_t d_gyro_xyz; + + /*******************read euler converted data*******************/ + /* variable used to read the euler h data output + as degree or radians*/ + double d_euler_data_h = BNO055_INIT_VALUE; + /* variable used to read the euler r data output + as degree or radians*/ + double d_euler_data_r = BNO055_INIT_VALUE; + /* variable used to read the euler p data output + as degree or radians*/ + double d_euler_data_p = BNO055_INIT_VALUE; + /* structure used to read the euler hrp data output + as as degree or radians */ + struct bno055_euler_double_t d_euler_hpr; + + /*********read linear acceleration converted data**********/ + /* variable used to read the linear accel x data output as m/s2*/ + double d_linear_accel_datax = BNO055_INIT_VALUE; + /* variable used to read the linear accel y data output as m/s2*/ + double d_linear_accel_datay = BNO055_INIT_VALUE; + /* variable used to read the linear accel z data output as m/s2*/ + double d_linear_accel_dataz = BNO055_INIT_VALUE; + /* structure used to read the linear accel xyz data output as m/s2*/ + struct bno055_linear_accel_double_t d_linear_accel_xyz; + + /********************Gravity converted data**********************/ + /* variable used to read the gravity sensor x data output as m/s2*/ + double d_gravity_data_x = BNO055_INIT_VALUE; + /* variable used to read the gravity sensor y data output as m/s2*/ + double d_gravity_data_y = BNO055_INIT_VALUE; + /* variable used to read the gravity sensor z data output as m/s2*/ + double d_gravity_data_z = BNO055_INIT_VALUE; + /* structure used to read the gravity xyz data output as m/s2*/ + struct bno055_gravity_double_t d_gravity_xyz; +/*---------------------------------------------------------------------------* + *********************** START INITIALIZATION ************************ + *--------------------------------------------------------------------------*/ + #ifdef BNO055_API +/* Based on the user need configure I2C interface. + * It is example code to explain how to use the bno055 API*/ + I2C_routine(); + #endif +/*--------------------------------------------------------------------------* + * This API used to assign the value/reference of + * the following parameters + * I2C address + * Bus Write + * Bus read + * Chip id + * Page id + * Accel revision id + * Mag revision id + * Gyro revision id + * Boot loader revision id + * Software revision id + *-------------------------------------------------------------------------*/ + comres = bno055_init(&bno055); + +/* For initializing the BNO sensor it is required to the operation mode + of the sensor as NORMAL + Normal mode can set from the register + Page - page0 + register - 0x3E + bit positions - 0 and 1*/ + power_mode = BNO055_POWER_MODE_NORMAL; + /* set the power mode as NORMAL*/ + comres += bno055_set_power_mode(power_mode); +/*----------------------------------------------------------------* +************************* END INITIALIZATION ************************* +*-----------------------------------------------------------------*/ + +/************************* START READ RAW SENSOR DATA****************/ + +/* Using BNO055 sensor we can read the following sensor data and + virtual sensor data + Sensor data: + Accel + Mag + Gyro + Virtual sensor data + Euler + Quaternion + Linear acceleration + Gravity sensor */ +/* For reading sensor raw data it is required to set the + operation modes of the sensor + operation mode can set from the register + page - page0 + register - 0x3D + bit - 0 to 3 + for sensor data read following operation mode have to set + * SENSOR MODE + *0x01 - BNO055_OPERATION_MODE_ACCONLY + *0x02 - BNO055_OPERATION_MODE_MAGONLY + *0x03 - BNO055_OPERATION_MODE_GYRONLY + *0x04 - BNO055_OPERATION_MODE_ACCMAG + *0x05 - BNO055_OPERATION_MODE_ACCGYRO + *0x06 - BNO055_OPERATION_MODE_MAGGYRO + *0x07 - BNO055_OPERATION_MODE_AMG + based on the user need configure the operation mode*/ + comres += bno055_set_operation_mode(BNO055_OPERATION_MODE_AMG); +/* Raw accel X, Y and Z data can read from the register + page - page 0 + register - 0x08 to 0x0D*/ + comres += bno055_read_accel_x(&accel_datax); + comres += bno055_read_accel_y(&accel_datay); + comres += bno055_read_accel_z(&accel_dataz); + comres += bno055_read_accel_xyz(&accel_xyz); +/* Raw mag X, Y and Z data can read from the register + page - page 0 + register - 0x0E to 0x13*/ + comres += bno055_read_mag_x(&mag_datax); + comres += bno055_read_mag_y(&mag_datay); + comres += bno055_read_mag_z(&mag_dataz); + comres += bno055_read_mag_xyz(&mag_xyz); +/* Raw gyro X, Y and Z data can read from the register + page - page 0 + register - 0x14 to 0x19*/ + comres += bno055_read_gyro_x(&gyro_datax); + comres += bno055_read_gyro_y(&gyro_datay); + comres += bno055_read_gyro_z(&gyro_dataz); + comres += bno055_read_gyro_xyz(&gyro_xyz); + +/************************* END READ RAW SENSOR DATA****************/ + +/************************* START READ RAW FUSION DATA ******** + For reading fusion data it is required to set the + operation modes of the sensor + operation mode can set from the register + page - page0 + register - 0x3D + bit - 0 to 3 + for sensor data read following operation mode have to set + *FUSION MODE + *0x08 - BNO055_OPERATION_MODE_IMUPLUS + *0x09 - BNO055_OPERATION_MODE_COMPASS + *0x0A - BNO055_OPERATION_MODE_M4G + *0x0B - BNO055_OPERATION_MODE_NDOF_FMC_OFF + *0x0C - BNO055_OPERATION_MODE_NDOF + based on the user need configure the operation mode*/ + comres += bno055_set_operation_mode(BNO055_OPERATION_MODE_NDOF); +/* Raw Euler H, R and P data can read from the register + page - page 0 + register - 0x1A to 0x1E */ + comres += bno055_read_euler_h(&euler_data_h); + comres += bno055_read_euler_r(&euler_data_r); + comres += bno055_read_euler_p(&euler_data_p); + comres += bno055_read_euler_hrp(&euler_hrp); +/* Raw Quaternion W, X, Y and Z data can read from the register + page - page 0 + register - 0x20 to 0x27 */ + comres += bno055_read_quaternion_w(&quaternion_data_w); + comres += bno055_read_quaternion_x(&quaternion_data_x); + comres += bno055_read_quaternion_y(&quaternion_data_y); + comres += bno055_read_quaternion_z(&quaternion_data_z); + comres += bno055_read_quaternion_wxyz(&quaternion_wxyz); +/* Raw Linear accel X, Y and Z data can read from the register + page - page 0 + register - 0x28 to 0x2D */ + comres += bno055_read_linear_accel_x(&linear_accel_data_x); + comres += bno055_read_linear_accel_y(&linear_accel_data_y); + comres += bno055_read_linear_accel_z(&linear_accel_data_z); + comres += bno055_read_linear_accel_xyz(&linear_acce_xyz); +/* Raw Gravity sensor X, Y and Z data can read from the register + page - page 0 + register - 0x2E to 0x33 */ + comres += bno055_read_gravity_x(&gravity_data_x); + comres += bno055_read_gravity_y(&gravity_data_y); + comres += bno055_read_gravity_z(&gravity_data_z); + comres += bno055_read_gravity_xyz(&gravity_xyz); +/************************* END READ RAW FUSION DATA ************/ + +/******************START READ CONVERTED SENSOR DATA****************/ +/* API used to read accel data output as double - m/s2 and mg + float functions also available in the BNO055 API */ + comres += bno055_convert_double_accel_x_msq(&d_accel_datax); + comres += bno055_convert_double_accel_x_mg(&d_accel_datax); + comres += bno055_convert_double_accel_y_msq(&d_accel_datay); + comres += bno055_convert_double_accel_y_mg(&d_accel_datay); + comres += bno055_convert_double_accel_z_msq(&d_accel_dataz); + comres += bno055_convert_double_accel_z_mg(&d_accel_dataz); + comres += bno055_convert_double_accel_xyz_msq(&d_accel_xyz); + comres += bno055_convert_double_accel_xyz_mg(&d_accel_xyz); + +/* API used to read mag data output as double - uT(micro Tesla) + float functions also available in the BNO055 API */ + comres += bno055_convert_double_mag_x_uT(&d_mag_datax); + comres += bno055_convert_double_mag_y_uT(&d_mag_datay); + comres += bno055_convert_double_mag_z_uT(&d_mag_dataz); + comres += bno055_convert_double_mag_xyz_uT(&d_mag_xyz); + +/* API used to read gyro data output as double - dps and rps + float functions also available in the BNO055 API */ + comres += bno055_convert_double_gyro_x_dps(&d_gyro_datax); + comres += bno055_convert_double_gyro_y_dps(&d_gyro_datay); + comres += bno055_convert_double_gyro_z_dps(&d_gyro_dataz); + comres += bno055_convert_double_gyro_x_rps(&d_gyro_datax); + comres += bno055_convert_double_gyro_y_rps(&d_gyro_datay); + comres += bno055_convert_double_gyro_z_rps(&d_gyro_dataz); + comres += bno055_convert_double_gyro_xyz_dps(&d_gyro_xyz); + comres += bno055_convert_double_gyro_xyz_rps(&d_gyro_xyz); + +/* API used to read Euler data output as double - degree and radians + float functions also available in the BNO055 API */ + comres += bno055_convert_double_euler_h_deg(&d_euler_data_h); + comres += bno055_convert_double_euler_r_deg(&d_euler_data_r); + comres += bno055_convert_double_euler_p_deg(&d_euler_data_p); + comres += bno055_convert_double_euler_h_rad(&d_euler_data_h); + comres += bno055_convert_double_euler_r_rad(&d_euler_data_r); + comres += bno055_convert_double_euler_p_rad(&d_euler_data_p); + comres += bno055_convert_double_euler_hpr_deg(&d_euler_hpr); + comres += bno055_convert_double_euler_hpr_rad(&d_euler_hpr); + +/* API used to read Linear acceleration data output as m/s2 + float functions also available in the BNO055 API */ + comres += bno055_convert_double_linear_accel_x_msq( + &d_linear_accel_datax); + comres += bno055_convert_double_linear_accel_y_msq( + &d_linear_accel_datay); + comres += bno055_convert_double_linear_accel_z_msq( + &d_linear_accel_dataz); + comres += bno055_convert_double_linear_accel_xyz_msq( + &d_linear_accel_xyz); + +/* API used to read Gravity sensor data output as m/s2 + float functions also available in the BNO055 API */ + comres += bno055_convert_gravity_double_x_msq(&d_gravity_data_x); + comres += bno055_convert_gravity_double_y_msq(&d_gravity_data_y); + comres += bno055_convert_gravity_double_z_msq(&d_gravity_data_z); + comres += bno055_convert_double_gravity_xyz_msq(&d_gravity_xyz); +/*-----------------------------------------------------------------------* +************************* START DE-INITIALIZATION *********************** +*-------------------------------------------------------------------------*/ +/* For de - initializing the BNO sensor it is required + to the operation mode of the sensor as SUSPEND + Suspend mode can set from the register + Page - page0 + register - 0x3E + bit positions - 0 and 1*/ + power_mode = BNO055_POWER_MODE_SUSPEND; + /* set the power mode as SUSPEND*/ + comres += bno055_set_power_mode(power_mode); + +/*---------------------------------------------------------------------* +************************* END DE-INITIALIZATION ********************** +*---------------------------------------------------------------------*/ +return comres; +} + +#ifdef BNO055_API +/*--------------------------------------------------------------------------* +* The following API is used to map the I2C bus read, write, delay and +* device address with global structure bno055_t +*-------------------------------------------------------------------------*/ +/*-------------------------------------------------------------------------* + * By using bno055 the following structure parameter can be accessed + * Bus write function pointer: BNO055_WR_FUNC_PTR + * Bus read function pointer: BNO055_RD_FUNC_PTR + * Delay function pointer: delay_msec + * I2C address: dev_addr + *--------------------------------------------------------------------------*/ +s8 I2C_routine(void) +{ + bno055.bus_write = BNO055_I2C_bus_write; + bno055.bus_read = BNO055_I2C_bus_read; + bno055.delay_msec = BNO055_delay_msek; + bno055.dev_addr = BNO055_I2C_ADDR1; + + return BNO055_INIT_VALUE; +} + +/************** I2C buffer length******/ + +#define I2C_BUFFER_LEN 8 +#define I2C0 5 +/*-------------------------------------------------------------------* +* +* This is a sample code for read and write the data by using I2C +* Use either I2C based on your need +* The device address defined in the bno055.h file +* +*--------------------------------------------------------------------*/ + +/* \Brief: The API is used as I2C bus write + * \Return : Status of the I2C write + * \param dev_addr : The device address of the sensor + * \param reg_addr : Address of the first register, + * will data is going to be written + * \param reg_data : It is a value hold in the array, + * will be used for write the value into the register + * \param cnt : The no of byte of data to be write + */ +s8 BNO055_I2C_bus_write(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt) +{ + s32 BNO055_iERROR = BNO055_INIT_VALUE; + u8 array[I2C_BUFFER_LEN]; + u8 stringpos = BNO055_INIT_VALUE; + + array[BNO055_INIT_VALUE] = reg_addr; + for (stringpos = BNO055_INIT_VALUE; stringpos < cnt; stringpos++) + array[stringpos + BNO055_I2C_BUS_WRITE_ARRAY_INDEX] = + *(reg_data + stringpos); + } + /* + * Please take the below APIs as your reference for + * write the data using I2C communication + * "BNO055_iERROR = I2C_WRITE_STRING(DEV_ADDR, ARRAY, CNT+1)" + * add your I2C write APIs here + * BNO055_iERROR is an return value of I2C read API + * Please select your valid return value + * In the driver BNO055_SUCCESS defined as 0 + * and FAILURE defined as -1 + * Note : + * This is a full duplex operation, + * The first read data is discarded, for that extra write operation + * have to be initiated. For that cnt+1 operation done + * in the I2C write string function + * For more information please refer data sheet SPI communication: + */ + return (s8)BNO055_iERROR; +} + + /* \Brief: The API is used as I2C bus read + * \Return : Status of the I2C read + * \param dev_addr : The device address of the sensor + * \param reg_addr : Address of the first register, + * will data is going to be read + * \param reg_data : This data read from the sensor, + * which is hold in an array + * \param cnt : The no of byte of data to be read + */ +s8 BNO055_I2C_bus_read(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt) +{ + s32 BNO055_iERROR = BNO055_INIT_VALUE; + u8 array[I2C_BUFFER_LEN] = {BNO055_INIT_VALUE}; + u8 stringpos = BNO055_INIT_VALUE; + + array[BNO055_INIT_VALUE] = reg_addr; + + /* Please take the below API as your reference + * for read the data using I2C communication + * add your I2C read API here. + * "BNO055_iERROR = I2C_WRITE_READ_STRING(DEV_ADDR, + * ARRAY, ARRAY, 1, CNT)" + * BNO055_iERROR is an return value of SPI write API + * Please select your valid return value + * In the driver BNO055_SUCCESS defined as 0 + * and FAILURE defined as -1 + */ + for (stringpos = BNO055_INIT_VALUE; stringpos < cnt; stringpos++) + *(reg_data + stringpos) = array[stringpos]; + return (s8)BNO055_iERROR; +} +/* Brief : The delay routine + * \param : delay in ms +*/ +void BNO055_delay_msek(u32 msek) +{ + /*Here you can write your own delay routine*/ +} + +#endif diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application-legacy.cpp b/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application-legacy.cpp new file mode 100644 index 0000000000..fae6ccc779 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application-legacy.cpp @@ -0,0 +1,879 @@ + + +// it is the old code which works fine but does not use embot::code::application + +/* + * Copyright (C) 2018 iCub Facility - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it + * website: www.robotcub.org + * Permission is granted to copy, distribute, and/or modify this program + * under the terms of the GNU General Public License, version 2 or any + * later version published by the Free Software Foundation. + * + * A copy of the license can be found at + * http://www.robotcub.org/icub/license/gpl.txt + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details +*/ + + +#undef TEST_ENABLED + +#undef TEST_HW_PGA308 +#undef TEST_HW_ADC +#undef TEST_HW_TIM +#undef TEST_HW_ONEWIRE +#undef TEST_DSP +#undef TEST_HW_SI7051 +#undef TEST_HW_BNO055 + +#if defined(TEST_ENABLED) +void tests_launcher_init(); +void tests_tick(); +#endif // #if defined(TEST_ENABLED) + +#include "embot_app_theLEDmanager.h" +#include "embot_app_canprotocol.h" +#include "embot_app_theCANboardInfo.h" + +#include "embot.h" + +#include "embot_common.h" +#include "embot_binary.h" +#include "embot_dsp.h" + +#include "stm32hal.h" +#include "embot_hw.h" +#include "embot_hw_sys.h" + +#include "embot_hw_FlashStorage.h" +#include "embot_sys_theStorage.h" + +#include "embot_app_theApplication.h" + +#include "embot_app_application_theCANparserBasic.h" + +#include "embot_app_application_theCANparserSTRAIN.h" +#include "embot_app_application_theCANparserIMU.h" +#include "embot_app_application_theCANparserTHERMO.h" + +#include "embot_app_application_theSTRAIN.h" +#include "embot_app_application_theIMU.h" +#include "embot_app_application_theTHERMO.h" + +#include "embot_hw_onewire.h" +#include "embot_hw_timer.h" +#include "embot_hw_pga308.h" +#include "embot_hw_adc.h" + + +#include "embot_hw_bsp_strain2.h" + +#if defined(TEST_ENABLED) + +#if defined(TEST_SI_ORIG) +//#include "embot_hw_si705x.h" +#else +#include "embot_hw_si7051.h" + +const embot::hw::SI7051::Sensor SI7051sensor = embot::hw::bsp::strain2::thermometerSGAUGES; +const embot::hw::SI7051::Config SI7051config = embot::hw::bsp::strain2::thermometerSGAUGESconfig; + +#endif +#endif // TEST_ENABLED + + +static const embot::app::canprotocol::versionOfAPPLICATION vAP = {2, 0, 3}; +static const embot::app::canprotocol::versionOfCANPROTOCOL vCP = {2, 0}; + +static void init(embot::sys::Task *t, void* param); +static void onidle(embot::sys::Task *t, void* param); +static void userdefonOSerror(void* param); + + +static const embot::sys::InitTask::Config initcfg = { 2048, init, nullptr }; +static const embot::sys::IdleTask::Config idlecfg = { 512, nullptr, nullptr, onidle }; +static const embot::core::Callback onOSerror = { userdefonOSerror, nullptr }; + +static const std::uint32_t address = embot::hw::flash::getpartition(embot::hw::FLASH::application).address; +constexpr bool initBSP = true; + +int main(void) +{ + embot::app::theApplication::Config config { address, initBSP, embot::core::time1millisec, {initcfg, idlecfg, onOSerror} }; + embot::app::theApplication &appl = embot::app::theApplication::getInstance(); + + // it prepares the system to run at a given flash address, it inits the hw::bsp, + // and finally start scheduler which sets the callback executed by the scheduler on OS error, + // starts the idle task and the init task. this latter is executed at maximum priority, launches + // its startup function and exits. + appl.execute(config); + + for(;;); +} + + +static embot::sys::EventTask* start_evt_based(void); +static void start_usr_services(embot::sys::EventTask* evtsk); +static void start_sys_services(); + + +static void init(embot::sys::Task *t, void* param) +{ + // start sys services: timer manager & callback manager + start_sys_services(); + + // make sure that the application and can protocol versions are synched + embot::app::theCANboardInfo &canbrdinfo = embot::app::theCANboardInfo::getInstance(); + canbrdinfo.synch(vAP, vCP); + + // start the main task + embot::sys::EventTask* maintask = start_evt_based(); + + // start the other services and link them to the main task + start_usr_services(maintask); +} + +static void onidle(embot::sys::Task *t, void* param) +{ + static int a = 0; + a++; +} + +static void userdefonOSerror(void *param) +{ + int code = 0; + embot::sys::theScheduler::getInstance().getOSerror(code); +} + + +static void start_sys_services() +{ + // start them both w/ default config; + embot::sys::theTimerManager::getInstance().start({}); + embot::sys::theCallbackManager::getInstance().start({}); +} + + +static void eventbasedtask_onevent(embot::sys::Task *t, embot::core::EventMask evtmsk, void *p); +static void eventbasedtask_init(embot::sys::Task *t, void *p); + +static const embot::core::Event evRXcanframe = 0x00000001 << 0; +static const embot::core::Event evSTRAINtick = 0x00000001 << 1; +static const embot::core::Event evSTRAINdataready = 0x00000001 << 2; +static const embot::core::Event evIMUtick = 0x00000001 << 3; +static const embot::core::Event evIMUdataready = 0x00000001 << 4; +static const embot::core::Event evTHERMOtick = 0x00000001 << 5; +static const embot::core::Event evTHERMOdataready = 0x00000001 << 6; + +static const std::uint8_t maxOUTcanframes = 48; + + +static void alerteventbasedtask(void *arg); + +static std::vector outframes; + + + +static embot::sys::EventTask* start_evt_based(void) +{ + // create the main task + embot::sys::EventTask* tsk = new embot::sys::EventTask; + const embot::core::relTime waitEventTimeout = 50*embot::core::time1millisec; + + embot::sys::EventTask::Config configEV; + + configEV.startup = eventbasedtask_init; + configEV.onevent = eventbasedtask_onevent; + configEV.param = nullptr; + configEV.stacksize = 4*1024; + configEV.priority = embot::sys::Priority::high200; + configEV.timeout = waitEventTimeout; + + // and start it + tsk->start(configEV); + + return tsk; +} + +static void start_usr_services(embot::sys::EventTask* evtsk) +{ +#if defined(TEST_ENABLED) + tests_launcher_init(); + return; +#endif // #if defined(TEST_ENABLED) + + // led manager + static const std::initializer_list allleds = {embot::hw::LED::one}; + embot::app::theLEDmanager &theleds = embot::app::theLEDmanager::getInstance(); + theleds.init(allleds); + theleds.get(embot::hw::LED::one).pulse(embot::core::time1second); + + // start canparser basic + embot::app::application::theCANparserBasic &canparserbasic = embot::app::application::theCANparserBasic::getInstance(); + embot::app::application::theCANparserBasic::Config configbasic; + canparserbasic.initialise(configbasic); + + // start agent of strain + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + embot::app::application::theSTRAIN::Config configstrain(evSTRAINtick, evSTRAINdataready, evtsk); + thestrain.initialise(configstrain); + + // start canparser strain and link it to its agent + embot::app::application::theCANparserSTRAIN &canparserstrain = embot::app::application::theCANparserSTRAIN::getInstance(); + embot::app::application::theCANparserSTRAIN::Config configparserstrain { &thestrain }; + canparserstrain.initialise(configparserstrain); + + // start agent of imu + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + embot::app::application::theIMU::Config configimu(embot::hw::bsp::strain2::imuBOSCH, embot::hw::bsp::strain2::imuBOSCHconfig, evIMUtick, evIMUdataready, evtsk); + theimu.initialise(configimu); + + // start canparser imu and link it to its agent + embot::app::application::theCANparserIMU &canparserimu = embot::app::application::theCANparserIMU::getInstance(); + embot::app::application::theCANparserIMU::Config configparserimu { &theimu }; + canparserimu.initialise(configparserimu); + + // start agent of thermo + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + embot::app::application::theTHERMO::Config configthermo(embot::hw::bsp::strain2::thermometerSGAUGES, embot::hw::bsp::strain2::thermometerSGAUGESconfig, evTHERMOtick, evTHERMOdataready, evtsk); + thethermo.initialise(configthermo); + + // start canparser thermo and link it to its agent + embot::app::application::theCANparserTHERMO &canparserthermo = embot::app::application::theCANparserTHERMO::getInstance(); + embot::app::application::theCANparserTHERMO::Config configparserthermo { &thethermo }; + canparserthermo.initialise(configparserthermo); + + // finally start can. i keep it as last because i dont want that the isr-handler calls its onrxframe() + // before the eventbasedtask is created. + embot::hw::can::Config canconfig; // default is tx/rxcapacity=8 + canconfig.txcapacity = maxOUTcanframes; + canconfig.onrxframe = embot::core::Callback(alerteventbasedtask, evtsk); + embot::hw::can::init(embot::hw::CAN::one, canconfig); + embot::hw::can::setfilters(embot::hw::CAN::one, embot::app::theCANboardInfo::getInstance().getCANaddress()); + +#if 1 + // it starts the tx of strain immediately + //embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.setTXperiod(10*embot::core::time1millisec); + thestrain.start(embot::app::canprotocol::analog::polling::Message_SET_TXMODE::StrainMode::txUncalibrated); +#endif +} + + +static void alerteventbasedtask(void *arg) +{ + embot::sys::EventTask* evtsk = reinterpret_cast(arg); + if(nullptr != evtsk) + { + evtsk->setEvent(evRXcanframe); + } +} + + +static void eventbasedtask_init(embot::sys::Task *t, void *p) +{ + embot::hw::result_t r = embot::hw::can::enable(embot::hw::CAN::one); + r = r; + outframes.reserve(maxOUTcanframes); +} + + + +static void eventbasedtask_onevent(embot::sys::Task *t, embot::core::EventMask eventmask, void *p) +{ + if(0 == eventmask) + { // timeout ... +#if defined(TEST_ENABLED) + tests_tick(); +#endif // #if defined(TEST_ENABLED) + return; + } + + // we clear the frames to be trasmitted + outframes.clear(); + + + if(true == embot::core::binary::mask::check(eventmask, evRXcanframe)) + { + embot::hw::can::Frame frame; + std::uint8_t remainingINrx = 0; + if(embot::hw::resOK == embot::hw::can::get(embot::hw::CAN::one, frame, remainingINrx)) + { + embot::app::application::theCANparserBasic &canparserbasic = embot::app::application::theCANparserBasic::getInstance(); + embot::app::application::theCANparserSTRAIN &canparserstrain = embot::app::application::theCANparserSTRAIN::getInstance(); + embot::app::application::theCANparserIMU &canparserimu = embot::app::application::theCANparserIMU::getInstance(); + embot::app::application::theCANparserTHERMO &canparserthermo = embot::app::application::theCANparserTHERMO::getInstance(); + // process w/ the basic parser, if not recognised call the parse specific of the board + if(true == canparserbasic.process(frame, outframes)) + { + } + else if(true == canparserstrain.process(frame, outframes)) + { + } + else if(true == canparserimu.process(frame, outframes)) + { + } + else if(true == canparserthermo.process(frame, outframes)) + { + } + + if(remainingINrx > 0) + { + t->setEvent(evRXcanframe); + } + } + } + + + if(true == embot::core::binary::mask::check(eventmask, evSTRAINtick)) + { + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evSTRAINdataready)) + { + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.processdata(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evIMUtick)) + { + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + theimu.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evIMUdataready)) + { + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + theimu.processdata(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evTHERMOtick)) + { + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + thethermo.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evTHERMOdataready)) + { + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + thethermo.processdata(outframes); + } + + // if we have any packet we transmit them + std::uint8_t num = outframes.size(); + if(num > 0) + { + for(std::uint8_t i=0; i= maxpulses) + { + static std::uint8_t x = 0; + num = 0; + embot::hw::timer::stop(timer2use); + embot::hw::timer::Config con; + con.onexpiry.callback = toggleled; + if(0 == x) + { + con.time = embot::core::time1microsec * 50; + embot::hw::timer::configure(timer2use, con); + x = 1; + } + else + { + con.time = embot::core::time1microsec * 100; + embot::hw::timer::configure(timer2use, con); + x = 0; + } + embot::hw::timer::start(timer2use); + } +} + +void test_tim_init(void) +{ + embot::hw::led::init(embot::hw::led::LED::one); + + embot::hw::led::on(embot::hw::led::LED::one); + embot::hw::led::off(embot::hw::led::LED::one); + + embot::hw::timer::Config con; + con.time = embot::core::time1microsec * 100; + con.onexpiry.callback = toggleled; + embot::hw::timer::init(timer2use, con); + embot::hw::timer::start(timer2use); +} + +#endif // defined(TEST_HW_TIM) + + + + +#if defined(TEST_DSP) +static std::int16_t mat1[3*3] = {0}; +static std::int16_t vec1[3*2] = {0}; +static std::int16_t vec2[3*2] = {0}; +static std::int16_t vin[3] = {0}; +static std::int16_t vout[3] = {0}; + +embot::dsp::q15::matrix ma1; +embot::dsp::q15::matrix ma2; +embot::dsp::q15::matrix ma3; + +embot::dsp::q15::matrix ve1; +embot::dsp::q15::matrix ve2; +#endif // #if defined(TEST_DSP) + +void ciao(void *p) +{ + static uint32_t io = 0; + io++; +} + +void tests_launcher_init() +{ +#if defined(TEST_HW_BNO055) + embot::hw::BNO055::init(embot::hw::bsp::strain2::imuBOSCH, embot::hw::bsp::strain2::imuBOSCHconfig); + + std::uint8_t dat08[16] = {0}; + embot::utils::Data data(dat08, 8); + + embot::hw::BNO055::Info info; + embot::hw::BNO055::get(embot::hw::bsp::strain2::imuBOSCH, info, embot::core::time1second); + + bool val = info.isvalid(); + val = val; + + embot::hw::BNO055::read(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::CHIP_ID, data, embot::core::time1second); + dat08[0] = dat08[0]; + + std::memset(dat08, 0, sizeof(dat08)); + embot::core::Callback cbk(ciao, nullptr); + embot::hw::BNO055::read(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::CHIP_ID, data, cbk); + for(;;) + { + if(true == embot::hw::BNO055::operationdone(embot::hw::bsp::strain2::imuBOSCH)) + { + break; + } + } + + + const embot::hw::BNO055::Mode mode2use = embot::hw::BNO055::Mode::NDOF; // NDOF // AMG // IMU //NDOF_FMC_OFF + std::memset(dat08, 0, sizeof(dat08)); + + embot::hw::BNO055::read(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::DATASET_START, data, embot::core::time1second); + embot::hw::BNO055::write(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::OPR_MODE, static_cast(mode2use), embot::core::time1second); + embot::hw::BNO055::read(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::DATASET_START, data, embot::core::time1second); + embot::hw::BNO055::read(embot::hw::bsp::strain2::imuBOSCH, embot::hw::BNO055::Register::DATASET_START, data, embot::core::time1second); + + embot::hw::sys::delay(10*1000); +#endif + +#if defined(TEST_HW_SI7051) + embot::hw::SI7051::init(SI7051sensor, SI7051config); +#endif + +#if defined(TEST_HW_PGA308) + + embot::hw::PGA308::Config pga308cfg; + + // common settings + pga308cfg.powerongpio = embot::hw::stm32GPIO(EN_2V8_GPIO_Port, EN_2V8_Pin); + pga308cfg.poweronstate = embot::hw::gpio::State::SET; + pga308cfg.onewireconfig.rate = embot::hw::onewire::Rate::tenKbps; + pga308cfg.onewireconfig.usepreamble = true; + pga308cfg.onewireconfig.preamble = 0x55; + + // from embot::hw::PGA308::one to embot::hw::PGA308::six + + // embot::hw::PGA308::zero + pga308cfg.onewirechannel = embot::hw::onewire::Channel::one; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN1_GPIO_Port, W_STRAIN1_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::one, pga308cfg); + + // embot::hw::PGA308::two + pga308cfg.onewirechannel = embot::hw::onewire::Channel::two; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN2_GPIO_Port, W_STRAIN2_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::two, pga308cfg); + + // embot::hw::PGA308::three + pga308cfg.onewirechannel = embot::hw::onewire::Channel::three; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN3_GPIO_Port, W_STRAIN3_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::three, pga308cfg); + + // embot::hw::PGA308::four + pga308cfg.onewirechannel = embot::hw::onewire::Channel::four; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN4_GPIO_Port, W_STRAIN4_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::four, pga308cfg); + + // embot::hw::PGA308::five + pga308cfg.onewirechannel = embot::hw::onewire::Channel::five; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN5_GPIO_Port, W_STRAIN5_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::five, pga308cfg); + + // embot::hw::PGA308::six + pga308cfg.onewirechannel = embot::hw::onewire::Channel::six; + pga308cfg.onewireconfig.gpio = embot::hw::stm32GPIO(W_STRAIN6_GPIO_Port, W_STRAIN6_Pin); + embot::hw::PGA308::init(embot::hw::PGA308::Amplifier::six, pga308cfg); + +#endif + + +#if defined(TEST_HW_ADC) + embot::hw::adc::Config adcConf; + adcConf.numberofitems = 6; + adcConf.destination = bufferSix; + adcConf.oncompletion.callback = adcdmadone_set; + embot::hw::adc::init(embot::hw::adc::Port::one, adcConf); +#endif // #if defined(TEST_HW_ADC) + + +#if defined(TEST_HW_TIM) + test_tim_init(); +#endif + + +#if defined(TEST_HW_ONEWIRE) + + embot::hw::onewire::Config con; + con.preamble = 0x55; + con.usepreamble = true; + con.rate = embot::hw::onewire::Rate::tenKbps; + con.gpio.load(W_STRAIN1_GPIO_Port, W_STRAIN1_Pin); + embot::hw::onewire::init(embot::hw::onewire::Channel::one, con); + +#endif + +} + +void counter(void *p) +{ + static int count = 0; + + count++; +} + +void tests_tick() +{ + +#if defined(TEST_HW_BNO055) + + embot::core::Time starttime = embot::sys::timeNow(); + embot::core::Time endtime = starttime; + + std::uint8_t value = 0; + std::uint8_t values[32] = {0}; + embot::utils::Data data; + const int ntimes = 1000; + embot::core::Callback cbk(counter, nullptr); + +#define MODE_DIRECT + + embot::hw::BNO055::Data datafull; + embot::core::Triple acc; + embot::core::Triple gyr; + embot::core::Triple eul; + std::uint8_t calibmag = 0; + std::uint8_t calibacc = 0; + int num = 0; + for(int i=0; i 666) + { + endtime ++; + starttime ++; + } + + + std::memset(items, 0xff, sizeof(items)); + embot::hw::adc::get(embot::hw::adc::Port::one, items); + +#endif // #if defined(TEST_HW_ADC) + + +#if defined(TEST_HW_ONEWIRE) + + embot::hw::onewire::write(embot::hw::onewire::Channel::one, 0x07, 0x1248); + +#endif // #if defined(TEST_HW_ONEWIRE) + +#if defined(TEST_DSP) + + static int sizE = 3; + + sizE ++; + + std::vector ciaO(sizE); + + ciaO[0] = 1; + + bool satu = true; + embot::dsp::Q15 ciao = embot::dsp::q15::convert(-0.5f, satu); + satu = satu; + + ma1.load(3, 3, mat1); + ma1.diagonal(embot::dsp::q15::negOne); + //ma1.fill(embot::dsp::q15::posOneHalf); + ma1.set(0, 0, embot::dsp::q15::posOneHalf+embot::dsp::q15::posOneFourth); + ma1.set(0, 1, embot::dsp::q15::posOneHalf+embot::dsp::q15::posOneFourth); + ma1.set(0, 2, embot::dsp::q15::negOneHalf); + + ve1.load(3, 1, vin); + ve1.set(0, 0, embot::dsp::q15::posOneNearly); + ve1.set(1, 0, embot::dsp::q15::posOneNearly); + ve1.set(2, 0, embot::dsp::q15::posOneNearly); + + ve2.load(3, 1, vout); + ve2.clear(); + + // now we multiply matrix 3x3 w/ vector 3x1 + + bool sat = false; + embot::dsp::q15::multiply(ma1, ve1, ve2, sat); + sat = sat; + + + ma2.load(3, 2, vec1); + ma2.fill(embot::dsp::q15::posOneHalf); + + ma3.load(3, 2, vec2); + ma3.clear(); + + bool saturated = false; + embot::dsp::q15::multiply(ma1, ma2, ma3, saturated); + saturated = saturated; + + double res = embot::dsp::q15::convert(ma3.get(0, 0)); + res = res; + embot::dsp::Q15 v = 0; + v = embot::dsp::q15::convert(-0.500, saturated); + res = embot::dsp::q15::convert(v); + v = embot::dsp::q15::convert(-0.250, saturated); + res = embot::dsp::q15::convert(v); + v = embot::dsp::q15::convert(-0.125, saturated); + res = embot::dsp::q15::convert(v); + v = embot::dsp::q15::posOneNearly; + res = embot::dsp::q15::convert(v); + res = res; + + v = embot::dsp::q15::opposite(v); + res = embot::dsp::q15::convert(v); + res = res; + + v = embot::dsp::q15::negOne; + res = embot::dsp::q15::convert(v); + v = embot::dsp::q15::opposite(v); + res = embot::dsp::q15::convert(v); + v = embot::dsp::q15::opposite(v); + res = embot::dsp::q15::convert(v); + + res = embot::dsp::q15::convert(v); + v = v; + +#endif // #if defined(TEST_DSP) + +} + +#endif // #if defined(TEST_ENABLED) + +/// + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application.cpp b/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application.cpp new file mode 100644 index 0000000000..92e17e13f9 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/main-strain2-application.cpp @@ -0,0 +1,318 @@ + +/* + * Copyright (C) 2019 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + + +#include "embot_app_skeleton_os_evthreadcan.h" + +// -------------------------------------------------------------------------------------------------------------------- +// config start + +constexpr embot::app::theCANboardInfo::applicationInfo applInfo +{ + embot::prot::can::versionOfAPPLICATION {2, 0, 15}, + embot::prot::can::versionOfCANPROTOCOL {2, 0} +}; + +constexpr std::uint16_t threadIDLEstacksize = 1*512; +constexpr std::uint16_t threadINITstacksize = 2048; +constexpr std::uint16_t threadEVNTstacksize = 4096; +constexpr std::uint8_t maxINPcanframes = 16; +constexpr std::uint8_t maxOUTcanframes = 48; +constexpr embot::core::relTime threadEVNTtimeout = 50*embot::core::time1millisec; + +static void *paramINIT = nullptr; +static void *paramIDLE = nullptr; +static void *paramERR = nullptr; +static void *paramEVNT = nullptr; + +constexpr embot::os::theTimerManager::Config tmcfg {}; +constexpr embot::os::theCallbackManager::Config cmcfg {}; + + +static const embot::app::skeleton::os::basic::sysConfig syscfg { threadINITstacksize, paramINIT, threadIDLEstacksize, paramIDLE, paramERR, tmcfg, cmcfg}; + +static const embot::app::skeleton::os::evthreadcan::evtConfig evtcfg { threadEVNTstacksize, paramEVNT, threadEVNTtimeout}; + +static const embot::app::skeleton::os::evthreadcan::canConfig cancfg { maxINPcanframes, maxOUTcanframes }; + +// config end +// -------------------------------------------------------------------------------------------------------------------- + + +class mySYS final : public embot::app::skeleton::os::evthreadcan::SYSTEMevtcan +{ +public: + mySYS(const embot::app::skeleton::os::basic::sysConfig &cfg) + : SYSTEMevtcan(cfg) {} + + void userdefOnIdle(embot::os::Thread *t, void* idleparam) const override; + void userdefonOSerror(void *errparam) const override; + void userdefInit_Extra(embot::os::EventThread* evthr, void *initparam) const override; +}; + + +class myEVT final : public embot::app::skeleton::os::evthreadcan::evThreadCAN +{ +public: + myEVT(const embot::app::skeleton::os::evthreadcan::evtConfig& ecfg, const embot::app::skeleton::os::evthreadcan::canConfig& ccfg, const embot::app::theCANboardInfo::applicationInfo& a) + : evThreadCAN(ecfg, ccfg, a) {} + + void userdefStartup(embot::os::Thread *t, void *param) const override; + void userdefOnTimeout(embot::os::Thread *t, embot::os::EventMask eventmask, void *param) const override; + void userdefOnEventRXcanframe(embot::os::Thread *t, embot::os::EventMask eventmask, void *param, const embot::prot::can::Frame &frame, std::vector &outframes) const override; + void userdefOnEventANYother(embot::os::Thread *t, embot::os::EventMask eventmask, void *param, std::vector &outframes) const override; +}; + + +static const mySYS mysys { syscfg }; +static const myEVT myevt { evtcfg, cancfg, applInfo }; +constexpr embot::app::skeleton::os::evthreadcan::CFG cfg{ &mysys, &myevt }; + +// -------------------------------------------------------------------------------------------------------------------- + +int main(void) +{ + embot::app::skeleton::os::evthreadcan::run(cfg); + for(;;); +} + + +// - here is the tailoring of the board. + + +#undef DEBUG_atstartup_tx_FTdata + +//#define DEBUG_atstartup_tx_FTdata 1 + +#undef ENABLE_IHAVEJUSTSTARTED + +#include "embot_hw_led.h" +#include "embot_hw_si7051.h" +#include "embot_hw_bno055.h" +#include "embot_hw_pga308.h" + +namespace embot { namespace hw { namespace bsp { namespace strain2 { + const embot::hw::LED ledBLUE = embot::hw::LED::one; + const embot::hw::SI7051 thermometerSGAUGES = embot::hw::SI7051::one; + const embot::hw::si7051::Config thermometerSGAUGESconfig {}; + const embot::hw::BNO055 imuBOSCH = embot::hw::BNO055::one; + const embot::hw::bno055::Config imuBOSCHconfig {}; +}}}} // namespace embot { namespace hw { namespace bsp { namespace strain2 { + +#include "embot_os_theScheduler.h" +#include "embot_app_theLEDmanager.h" +#include "embot_app_application_theCANparserBasic.h" + +#include "embot_app_application_theCANparserSTRAIN.h" +#include "embot_app_application_theCANparserIMU.h" +#include "embot_app_application_theCANparserTHERMO.h" + +#include "embot_app_application_theSTRAIN.h" +#include "embot_app_application_theIMU.h" +#include "embot_app_application_theTHERMO.h" + +#include "embot_app_application_theCANtracer.h" + + +constexpr embot::os::Event evSTRAINtick = 0x00000001 << 1; +constexpr embot::os::Event evSTRAINdataready = 0x00000001 << 2; +constexpr embot::os::Event evIMUtick = 0x00000001 << 3; +constexpr embot::os::Event evIMUdataready = 0x00000001 << 4; +constexpr embot::os::Event evTHERMOtick = 0x00000001 << 5; +constexpr embot::os::Event evTHERMOdataready = 0x00000001 << 6; + +#if defined(ENABLE_IHAVEJUSTSTARTED) +constexpr embot::os::Event evIHAVEjuststarted = 0x00000001 << 7; +static void ihavejuststarted_init(embot::os::EventThread* evthr); +static void ihavejuststarted_tick(std::vector &outframes); +#endif + +void mySYS::userdefOnIdle(embot::os::Thread *t, void* idleparam) const +{ + static int a = 0; + a++; +} + +void mySYS::userdefonOSerror(void *errparam) const +{ + static int code = 0; + embot::os::theScheduler::getInstance().getOSerror(code); + for(;;); +} + + +void mySYS::userdefInit_Extra(embot::os::EventThread* evthr, void *initparam) const +{ + // inside the init thread: put the init of many things ... + + // led manager + static const std::initializer_list allleds = {embot::hw::LED::one}; + embot::app::theLEDmanager &theleds = embot::app::theLEDmanager::getInstance(); + theleds.init(allleds); + theleds.get(embot::hw::LED::one).pulse(embot::core::time1second); + + // init of can basic paser + embot::app::application::theCANparserBasic::getInstance().initialise({}); + + // init agent of strain + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + embot::app::application::theSTRAIN::Config configstrain(evSTRAINtick, evSTRAINdataready, evthr); + thestrain.initialise(configstrain); + + // init canparser strain and link it to its agent + embot::app::application::theCANparserSTRAIN &canparserstrain = embot::app::application::theCANparserSTRAIN::getInstance(); + embot::app::application::theCANparserSTRAIN::Config configparserstrain { &thestrain }; + canparserstrain.initialise(configparserstrain); + + // init agent of imu + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + embot::app::application::theIMU::Config configimu(embot::hw::bsp::strain2::imuBOSCH, embot::hw::bsp::strain2::imuBOSCHconfig, evIMUtick, evIMUdataready, evthr); + theimu.initialise(configimu); + + // init canparser imu and link it to its agent + embot::app::application::theCANparserIMU &canparserimu = embot::app::application::theCANparserIMU::getInstance(); + embot::app::application::theCANparserIMU::Config configparserimu { &theimu }; + canparserimu.initialise(configparserimu); + + // init agent of thermo + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + embot::app::application::theTHERMO::Config configthermo(embot::hw::bsp::strain2::thermometerSGAUGES, embot::hw::bsp::strain2::thermometerSGAUGESconfig, evTHERMOtick, evTHERMOdataready, evthr); + thethermo.initialise(configthermo); + + // init canparser thermo and link it to its agent + embot::app::application::theCANparserTHERMO &canparserthermo = embot::app::application::theCANparserTHERMO::getInstance(); + embot::app::application::theCANparserTHERMO::Config configparserthermo { &thethermo }; + canparserthermo.initialise(configparserthermo); + +#if defined(ENABLE_IHAVEJUSTSTARTED) + // init service IHaveJustStarted + ihavejuststarted_init(evthr); +#endif +} + +void myEVT::userdefStartup(embot::os::Thread *t, void *param) const +{ + // inside startup of evnt thread: put the init of many things ... + + // maybe we start the tx of ft data straight away +#if defined(DEBUG_atstartup_tx_FTdata) + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.setTXperiod(10*embot::core::time1millisec); + thestrain.start(embot::prot::can::analog::polling::Message_SET_TXMODE::StrainMode::txUncalibrated); +#endif +} + + +void myEVT::userdefOnTimeout(embot::os::Thread *t, embot::os::EventMask eventmask, void *param) const +{ + static uint32_t cnt = 0; + cnt++; +} + + +void myEVT::userdefOnEventRXcanframe(embot::os::Thread *t, embot::os::EventMask eventmask, void *param, const embot::prot::can::Frame &frame, std::vector &outframes) const +{ + // process w/ the basic parser. if not recognised call the parsers specific of the board + if(true == embot::app::application::theCANparserBasic::getInstance().process(frame, outframes)) + { + } + if(true == embot::app::application::theCANparserSTRAIN::getInstance().process(frame, outframes)) + { + } + else if(true == embot::app::application::theCANparserIMU::getInstance().process(frame, outframes)) + { + } + else if(true == embot::app::application::theCANparserTHERMO::getInstance().process(frame, outframes)) + { + } +} + +void myEVT::userdefOnEventANYother(embot::os::Thread *t, embot::os::EventMask eventmask, void *param, std::vector &outframes) const +{ + if(true == embot::core::binary::mask::check(eventmask, evSTRAINtick)) + { + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evSTRAINdataready)) + { + embot::app::application::theSTRAIN &thestrain = embot::app::application::theSTRAIN::getInstance(); + thestrain.processdata(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evIMUtick)) + { + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + theimu.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evIMUdataready)) + { + embot::app::application::theIMU &theimu = embot::app::application::theIMU::getInstance(); + theimu.processdata(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evTHERMOtick)) + { + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + thethermo.tick(outframes); + } + + if(true == embot::core::binary::mask::check(eventmask, evTHERMOdataready)) + { + embot::app::application::theTHERMO &thethermo = embot::app::application::theTHERMO::getInstance(); + thethermo.processdata(outframes); + } + +#if defined(ENABLE_IHAVEJUSTSTARTED) + if(true == embot::core::binary::mask::check(eventmask, evIHAVEjuststarted)) + { + ihavejuststarted_tick(outframes); + } +#endif + +} + + +#if defined(ENABLE_IHAVEJUSTSTARTED) + +constexpr uint32_t ntimes = 5; +constexpr embot::core::Time deltatime = 3 * embot::core::time1second; +uint32_t times = 0; + +embot::os::Timer * _tmr {nullptr}; +static void ihavejuststarted_init(embot::os::EventThread* evthr) +{ + times = 0; + _tmr = new embot::os::Timer; + _tmr->start({deltatime, {embot::os::EventToThread{evIHAVEjuststarted, evthr}}, embot::os::Timer::Mode::someshots, ntimes}); +} + +//action.load(embot::os::EventToThread(pImpl->config.tickevent, pImpl->config.tothread)); +//evIHAVEjuststarted + +static void ihavejuststarted_tick(std::vector &outframes) +{ + char ss[64] = {0}; + uint64_t tt = embot::core::now(); + uint32_t mm = tt /= 1000; + uint32_t s = mm/1000; + uint32_t m = mm - s*1000; + + snprintf(ss, sizeof(ss), "i woke up %ds%dm ago", s, m); + embot::app::theCANtracer &tracer = embot::app::theCANtracer::getInstance(); + tracer.print(ss, outframes); +} + +#endif // #if defined(ENABLE_IHAVEJUSTSTARTED) + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_continuous.h b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_continuous.h new file mode 100644 index 0000000000..c20df6d5a2 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_continuous.h @@ -0,0 +1,131 @@ +/* Copyright 1990-2014 The MathWorks, Inc. */ + +/* + * File: rtw_continuous.h + * + * Abstract: + * Type definitions for continuous-time support. + * + */ + +#ifndef RTW_CONTINUOUS_H__ +#define RTW_CONTINUOUS_H__ + +#ifdef MATLAB_MEX_FILE +#include "tmwtypes.h" +#else +#include "rtwtypes.h" +#endif + +/* For models registering MassMatrix */ +typedef enum { + SS_MATRIX_NONE, + SS_MATRIX_CONSTANT, + SS_MATRIX_TIMEDEP, + SS_MATRIX_STATEDEP +} ssMatrixType; + +typedef enum { + SOLVER_MODE_AUTO, /* only occurs in + mdlInitializeSizes/mdlInitializeSampleTimes */ + SOLVER_MODE_SINGLETASKING, + SOLVER_MODE_MULTITASKING +} SolverMode; + +typedef enum { + MINOR_TIME_STEP, + MAJOR_TIME_STEP +} SimTimeStep; + +/* ============================================================================= + * Model methods object + * ============================================================================= + */ +typedef void (*rtMdlInitializeSizesFcn)(void *rtModel); +typedef void (*rtMdlInitializeSampleTimesFcn)(void *rtModel); +typedef void (*rtMdlStartFcn)(void *rtModel); +typedef void (*rtMdlOutputsFcn)(void *rtModel, int_T tid); +typedef void (*rtMdlUpdateFcn)(void *rtModel, int_T tid); +typedef void (*rtMdlDerivativesFcn)(void *rtModel); +typedef void (*rtMdlProjectionFcn)(void *rtModel); +typedef void (*rtMdlMassMatrixFcn)(void *rtModel); +typedef void (*rtMdlForcingFunctionFcn)(void *rtModel); +typedef void (*rtMdlTerminateFcn)(void *rtModel); +#ifdef RT_MALLOC +typedef real_T (*rtMdlDiscreteEventsFcn)(void *pModel, + int_T rtmNumSampTimes, + void *rtmTimingData, + int_T *rtmSampleHitPtr, + int_T *rtmPerTaskSampleHits); +#endif + +typedef struct _RTWRTModelMethodsInfo_tag { + void *rtModelPtr; + rtMdlInitializeSizesFcn rtmInitSizesFcn; + rtMdlInitializeSampleTimesFcn rtmInitSampTimesFcn; + rtMdlStartFcn rtmStartFcn; + rtMdlOutputsFcn rtmOutputsFcn; + rtMdlUpdateFcn rtmUpdateFcn; + rtMdlDerivativesFcn rtmDervisFcn; + rtMdlProjectionFcn rtmProjectionFcn; + rtMdlMassMatrixFcn rtmMassMatrixFcn; + rtMdlForcingFunctionFcn rtmForcingFunctionFcn; + rtMdlTerminateFcn rtmTerminateFcn; +#ifdef RT_MALLOC + rtMdlDiscreteEventsFcn rtmDiscreteEventsFcn; +#endif +} RTWRTModelMethodsInfo; + +#define rtmiSetRTModelPtr(M,rtmp) ((M).rtModelPtr = (rtmp)) +#define rtmiGetRTModelPtr(M) (M).rtModelPtr + +#define rtmiSetInitSizesFcn(M,fp) \ + ((M).rtmInitSizesFcn = ((rtMdlInitializeSizesFcn)(fp))) +#define rtmiSetInitSampTimesFcn(M,fp) \ + ((M).rtmInitSampTimesFcn = ((rtMdlInitializeSampleTimesFcn)(fp))) +#define rtmiSetStartFcn(M,fp) \ + ((M).rtmStartFcn = ((rtMdlStartFcn)(fp))) +#define rtmiSetOutputsFcn(M,fp) \ + ((M).rtmOutputsFcn = ((rtMdlOutputsFcn)(fp))) +#define rtmiSetUpdateFcn(M,fp) \ + ((M).rtmUpdateFcn = ((rtMdlUpdateFcn)(fp))) +#define rtmiSetDervisFcn(M,fp) \ + ((M).rtmDervisFcn = ((rtMdlDerivativesFcn)(fp))) +#define rtmiSetProjectionFcn(M,fp) \ + ((M).rtmProjectionFcn = ((rtMdlProjectionFcn)(fp))) +#define rtmiSetMassMatrixFcn(M,fp) \ + ((M).rtmMassMatrixFcn = ((rtMdlMassMatrixFcn)(fp))) +#define rtmiSetForcingFunctionFcn(M,fp) \ + ((M).rtmForcingFunctionFcn = ((rtMdlForcingFunctionFcn)(fp))) +#define rtmiSetTerminateFcn(M,fp) \ + ((M).rtmTerminateFcn = ((rtMdlTerminateFcn)(fp))) +#ifdef RT_MALLOC +#define rtmiSetDiscreteEventsFcn(M,fp) \ + ((M).rtmDiscreteEventsFcn = ((rtMdlDiscreteEventsFcn)(fp))) +#endif + +#define rtmiInitializeSizes(M) \ + ((*(M).rtmInitSizesFcn)((M).rtModelPtr)) +#define rtmiInitializeSampleTimes(M) \ + ((*(M).rtmInitSampTimesFcn)((M).rtModelPtr)) +#define rtmiStart(M) \ + ((*(M).rtmStartFcn)((M).rtModelPtr)) +#define rtmiOutputs(M, tid) \ + ((*(M).rtmOutputsFcn)((M).rtModelPtr,tid)) +#define rtmiUpdate(M, tid) \ + ((*(M).rtmUpdateFcn)((M).rtModelPtr,tid)) +#define rtmiDerivatives(M) \ + ((*(M).rtmDervisFcn)((M).rtModelPtr)) +#define rtmiProjection(M) \ + ((*(M).rtmProjectionFcn)((M).rtModelPtr)) +#define rtmiMassMatrix(M) \ + ((*(M).rtmMassMatrixFcn)((M).rtModelPtr)) +#define rtmiForcingFunction(M) \ + ((*(M).rtmForcingFunctionFcn)((M).rtModelPtr)) +#define rtmiTerminate(M) \ + ((*(M).rtmTerminateFcn)((M).rtModelPtr)) +#ifdef RT_MALLOC +#define rtmiDiscreteEvents(M,x1,x2,x3,x4) \ + ((*(M).rtmDiscreteEventsFcn)((M).rtModelPtr,(x1),(x2),(x3),(x4))) +#endif +#endif /* __RTW_CONTINUOUS_H__ */ diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_solver.h b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_solver.h new file mode 100644 index 0000000000..7be701e537 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtw_solver.h @@ -0,0 +1,267 @@ +/* + * File: rtw_solver.h + * + * Abstract: + * Type definitions for continuous-time solver support. + * + */ + +/* Copyright 1990-2017 The MathWorks, Inc. */ + +#ifndef RTW_SOLVER_H__ +#define RTW_SOLVER_H__ + +#include "rtw_continuous.h" + +/* ============================================================================= + * Solver object + * ============================================================================= + */ +#ifndef NO_FLOATS /* ERT integer-only */ +/* + * Enum for solver tolerance + */ +typedef enum { + SL_SOLVER_TOLERANCE_AUTO = 0, /* Set Automatically by Solver */ + SL_SOLVER_TOLERANCE_LOCAL = 1, /* Set Locally, e.g., by Blocks */ + SL_SOLVER_TOLERANCE_GLOBAL = 2, /* Set Globally, e.g., by Block Diagram */ + SL_SOLVER_TOLERANCE_UNDEFINED = 255 /* Signal uninitialized */ +} SL_SolverToleranceControlFlag_T; + + +/* + * Enum for jacobian method control + */ +typedef enum { + SL_JM_BD_AUTO = 0, + SL_JM_BD_SPARSE_PERTURBATION, + SL_JM_BD_FULL_PERTURBATION, + SL_JM_BD_SPARSE_ANALYTICAL, + SL_JM_BD_FULL_ANALYTICAL +} slJmBdControl; + + +typedef struct _ssSolverInfo_tag { + void *rtModelPtr; + + SimTimeStep *simTimeStepPtr; + void *solverData; + const char_T *solverName; + boolean_T isVariableStepSolver; + boolean_T solverNeedsReset; + SolverMode solverMode; + + time_T solverStopTime; + time_T *stepSizePtr; + time_T minStepSize; + time_T maxStepSize; + time_T fixedStepSize; + + int_T solverShapePreserveControl; + int_T solverMaxConsecutiveMinStep; + int_T maxNumMinSteps; + int_T solverMaxOrder; + real_T solverConsecutiveZCsStepRelTol; + int_T solverMaxConsecutiveZCs; + + int_T solverExtrapolationOrder; + int_T solverNumberNewtonIterations; + + int_T solverRefineFactor; + real_T solverRelTol; + real_T unused_real_T_1; + + real_T **dXPtr; + time_T **tPtr; + + int_T *numContStatesPtr; + real_T **contStatesPtr; + + int_T* numPeriodicContStatesPtr; + int_T** periodicContStateIndicesPtr; + real_T** periodicContStateRangesPtr; + + real_T* zcSignalVector; + uint8_T* zcEventsVector; + uint8_T* zcSignalAttrib; + int_T zcSignalVectorLength; + uint8_T* reserved; + + boolean_T foundContZcEvents; + boolean_T isAtLeftPostOfContZcEvent; + boolean_T isAtRightPostOfContZcEvent; + boolean_T adaptiveZcDetection; + + int_T numZcSignals; + + boolean_T stateProjection; + boolean_T robustResetMethod; /* user's preference */ + boolean_T updateJacobianAtReset; /* S-Fcn request (sticky) */ + boolean_T consistencyChecking; + + ssMatrixType massMatrixType; + int_T massMatrixNzMax; + int_T* massMatrixIr; + int_T* massMatrixJc; + real_T* massMatrixPr; + + const char_T **errStatusPtr; + + RTWRTModelMethodsInfo *modelMethodsPtr; + real_T zcThreshold; + int_T zeroCrossAlgorithm; + int_T consecutiveZCsError; + boolean_T CTOutputIncnstWithState; + boolean_T isComputingJacobian; + slJmBdControl solverJacobianMethodControl; + int_T ignoredZcDiagnostic; + int_T maskedZcDiagnostic; + boolean_T isOutputMethodComputed; + int_T maxZcBracketingIterations; + boolean_T isMinorOutputWithModeChange; + int_T maxZcPerIntegrationInterval; +} ssSolverInfo; + +/* Support old name RTWSolverInfo */ +typedef ssSolverInfo RTWSolverInfo; + +#define rtsiSetRTModelPtr(S,rtmp) ((S)->rtModelPtr = (rtmp)) +#define rtsiGetRTModelPtr(S) (S)->rtModelPtr + +#define rtsiSetSimTimeStepPtr(S,stp) ((S)->simTimeStepPtr = (stp)) +#define rtsiGetSimTimeStepPtr(S) ((S)->simTimeStepPtr) +#define rtsiGetSimTimeStep(S) *((S)->simTimeStepPtr) +#define rtsiSetSimTimeStep(S,st) (*((S)->simTimeStepPtr) = (st)) + +#define rtsiSetSolverData(S,sd) ((S)->solverData = (sd)) +#define rtsiGetSolverData(S) (S)->solverData + +#define rtsiSetSolverName(S,sn) ((S)->solverName = (sn)) +#define rtsiGetSolverName(S) (S)->solverName + +#define rtsiSetVariableStepSolver(S,vs) ((S)->isVariableStepSolver = (vs)) +#define rtsiIsVariableStepSolver(S) (S)->isVariableStepSolver + +#define rtsiSetSolverNeedsReset(S,sn) ((S)->solverNeedsReset = (sn)) +#define rtsiGetSolverNeedsReset(S) (S)->solverNeedsReset + +#define rtsiSetContTimeOutputInconsistentWithStateAtMajorStep(S,sn) ((S)->CTOutputIncnstWithState = (sn)) +#define rtsiGetContTimeOutputInconsistentWithStateAtMajorStep(S) (S)->CTOutputIncnstWithState + +#define rtsiSetBlkStateChange(S,sn) ((S)->CTOutputIncnstWithState = (sn)) +#define rtsiGetBlkStateChange(S) (S)->CTOutputIncnstWithState + +#define rtsiSetBlockStateForSolverChangedAtMajorStep(S,sn) ((S)->solverNeedsReset = (sn)) +#define rtsiGetBlockStateForSolverChangedAtMajorStep(S) (S)->solverNeedsReset + +#define rtsiSetSolverMode(S,sm) ((S)->solverMode = (sm)) +#define rtsiGetSolverMode(S) (S)->solverMode + +#define rtsiSetSolverStopTime(S,st) ((S)->solverStopTime = (st)) +#define rtsiGetSolverStopTime(S) (S)->solverStopTime + +#define rtsiSetStepSizePtr(S,ssp) ((S)->stepSizePtr = (ssp)) +#define rtsiSetStepSize(S,ss) (*((S)->stepSizePtr) = (ss)) +#define rtsiGetStepSize(S) *((S)->stepSizePtr) + +#define rtsiSetMinStepSize(S,ss) (((S)->minStepSize = (ss))) +#define rtsiGetMinStepSize(S) (S)->minStepSize + +#define rtsiSetMaxStepSize(S,ss) ((S)->maxStepSize = (ss)) +#define rtsiGetMaxStepSize(S) (S)->maxStepSize + +#define rtsiSetFixedStepSize(S,ss) ((S)->fixedStepSize = (ss)) +#define rtsiGetFixedStepSize(S) (S)->fixedStepSize + +#define rtsiSetMaxNumMinSteps(S,mns) ((S)->maxNumMinSteps = (mns)) +#define rtsiGetMaxNumMinSteps(S) (S)->maxNumMinSteps + +#define rtsiSetSolverMaxOrder(S,smo) ((S)->solverMaxOrder = (smo)) +#define rtsiGetSolverMaxOrder(S) (S)->solverMaxOrder + +#define rtsiSetSolverJacobianMethodControl(S,smcm) (ssGetSolverInfo(S)->solverJacobianMethodControl = (smcm)) +#define rtsiGetSolverJacobianMethodControl(S) ssGetSolverInfo(S)->solverJacobianMethodControl + +#define rtsiSetSolverShapePreserveControl(S,smcm) (ssGetSolverInfo(S)->solverShapePreserveControl = (smcm)) +#define rtsiGetSolverShapePreserveControl(S) ssGetSolverInfo(S)->solverShapePreserveControl + +#define rtsiSetSolverConsecutiveZCsStepRelTol(S,scr) (ssGetSolverInfo(S)->solverConsecutiveZCsStepRelTol = (scr)) +#define rtsiGetSolverConsecutiveZCsStepRelTol(S) ssGetSolverInfo(S)->solverConsecutiveZCsStepRelTol + +#define rtsiSetSolverMaxConsecutiveZCs(S,smcz) (ssGetSolverInfo(S)->solverMaxConsecutiveZCs = (smcz)) +#define rtsiGetSolverMaxConsecutiveZCs(S) ssGetSolverInfo(S)->solverMaxConsecutiveZCs + +#define rtsiSetSolverMaxConsecutiveMinStep(S,smcm) (ssGetSolverInfo(S)->solverMaxConsecutiveMinStep = (smcm)) +#define rtsiGetSolverMaxConsecutiveMinStep(S) ssGetSolverInfo(S)->solverMaxConsecutiveMinStep + +#define rtsiSetSolverExtrapolationOrder(S,seo) ((S)->solverExtrapolationOrder = (seo)) +#define rtsiGetSolverExtrapolationOrder(S) (S)->solverExtrapolationOrder + +#define rtsiSetSolverNumberNewtonIterations(S,nni) ((S)->solverNumberNewtonIterations = (nni)) +#define rtsiGetSolverNumberNewtonIterations(S) (S)->solverNumberNewtonIterations + +#define rtsiSetSolverRefineFactor(S,smo) ((S)->solverRefineFactor = (smo)) +#define rtsiGetSolverRefineFactor(S) (S)->solverRefineFactor + +#define rtsiSetSolverRelTol(S,smo) ((S)->solverRelTol = (smo)) +#define rtsiGetSolverRelTol(S) (S)->solverRelTol + +#define rtsiSetSolverMassMatrixType(S,type) ((S)->massMatrixType = (type)) +#define rtsiGetSolverMassMatrixType(S) (S)->massMatrixType + +#define rtsiSetSolverMassMatrixNzMax(S,nzMax) ((S)->massMatrixNzMax = (nzMax)) +#define rtsiGetSolverMassMatrixNzMax(S) (S)->massMatrixNzMax + +#define rtsiSetSolverMassMatrixIr(S,ir) ((S)->massMatrixIr = (ir)) +#define rtsiGetSolverMassMatrixIr(S) (S)->massMatrixIr + +#define rtsiSetSolverMassMatrixJc(S,jc) ((S)->massMatrixJc = (jc)) +#define rtsiGetSolverMassMatrixJc(S) (S)->massMatrixJc + +#define rtsiSetSolverMassMatrixPr(S,pr) ((S)->massMatrixPr = (pr)) +#define rtsiGetSolverMassMatrixPr(S) (S)->massMatrixPr + +#define rtsiSetdXPtr(S,dxp) ((S)->dXPtr = (dxp)) +#define rtsiSetdX(S,dx) (*((S)->dXPtr) = (dx)) +#define rtsiGetdX(S) *((S)->dXPtr) + +#define rtsiSetTPtr(S,tp) ((S)->tPtr = (tp)) +#define rtsiSetT(S,t) ((*((S)->tPtr))[0] = (t)) +#define rtsiGetT(S) (*((S)->tPtr))[0] + +#define rtsiSetContStatesPtr(S,cp) ((S)->contStatesPtr = (cp)) +#define rtsiGetContStates(S) *((S)->contStatesPtr) + +#define rtsiSetNumContStatesPtr(S,cp) ((S)->numContStatesPtr = (cp)) +#define rtsiGetNumContStates(S) *((S)->numContStatesPtr) + +#define rtsiSetNumPeriodicContStatesPtr(S,cp) ((S)->numPeriodicContStatesPtr = (cp)) +#define rtsiGetNumPeriodicContStates(S) *((S)->numPeriodicContStatesPtr) + +#define rtsiSetPeriodicContStateIndicesPtr(S,cp) ((S)->periodicContStateIndicesPtr = (cp)) +#define rtsiGetPeriodicContStateIndices(S) *((S)->periodicContStateIndicesPtr) + +#define rtsiSetPeriodicContStateRangesPtr(S,cp) ((S)->periodicContStateRangesPtr = (cp)) +#define rtsiGetPeriodicContStateRanges(S) *((S)->periodicContStateRangesPtr) + +#define rtsiSetErrorStatusPtr(S,esp) ((S)->errStatusPtr = (esp)) +#define rtsiSetErrorStatus(S,es) (*((S)->errStatusPtr) = (es)) +#define rtsiGetErrorStatus(S) *((S)->errStatusPtr) + +#define rtsiSetModelMethodsPtr(S,mmp) ((S)->modelMethodsPtr = (mmp)) +#define rtsiGetModelMethodsPtr(S) (S)->modelMethodsPtr + +#define rtsiSetSolverComputingJacobian(S,val) ((S)->isComputingJacobian = (val)) +#define rtsiIsSolverComputingJacobian(S) (S)->isComputingJacobian + +#define rtsiSetSolverOutputComputed(S,val) ((S)->isOutputMethodComputed = (val)) +#define rtsiIsSolverOutputComputed(S) (S)->isOutputMethodComputed + +#define rtsiSetIsMinorOutputWithModeChange(S,sn) ((S)->isMinorOutputWithModeChange = (sn)) +#define rtsiGetIsMinorOutputWithModeChange(S) (S)->isMinorOutputWithModeChange + +#define rtsiGetIsOkayToUpdateMode(S) (rtsiGetSimTimeStep(S) == MAJOR_TIME_STEP || rtsiGetIsMinorOutputWithModeChange(S)) + +#endif /* !NO_FLOATS */ + +#endif /* RTW_SOLVER_H__ */ diff --git a/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtwtypes.h b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtwtypes.h new file mode 100644 index 0000000000..50c0c5c027 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/application/src/rtwtypes.h @@ -0,0 +1,106 @@ +// +// Non-Degree Granting Education License -- for use at non-degree +// granting, nonprofit, educational organizations only. Not for +// government, commercial, or other organizational use. +// +// File: rtwtypes.h +// +// Code generated for Simulink model 'adc2ft'. +// +// Model version : 2.41 +// Simulink Coder version : 9.5 (R2021a) 14-Nov-2020 +// C/C++ source code generated on : Tue Apr 13 09:39:18 2021 +// +// Target selection: ert.tlc +// Embedded hardware selection: ARM Compatible->ARM Cortex-M +// Code generation objectives: +// 1. Execution efficiency +// 2. RAM efficiency +// Validation result: Not run +// + +#ifndef RTWTYPES_H +#define RTWTYPES_H + +// Logical type definitions +#if (!defined(__cplusplus)) +#ifndef false +#define false (0U) +#endif + +#ifndef true +#define true (1U) +#endif +#endif + +//=======================================================================* +// Target hardware information +// Device type: ARM Compatible->ARM Cortex-M +// Number of bits: char: 8 short: 16 int: 32 +// long: 32 long long: 64 +// native word size: 32 +// Byte ordering: LittleEndian +// Signed integer division rounds to: Zero +// Shift right on a signed integer as arithmetic shift: on +// ======================================================================= + +//=======================================================================* +// Fixed width word size data types: * +// int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * +// uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * +// real32_T, real64_T - 32 and 64 bit floating point numbers * +// ======================================================================= +typedef signed char int8_T; +typedef unsigned char uint8_T; +typedef short int16_T; +typedef unsigned short uint16_T; +typedef int int32_T; +typedef unsigned int uint32_T; +typedef long long int64_T; +typedef unsigned long long uint64_T; +typedef float real32_T; +typedef double real64_T; + +//===========================================================================* +// Generic type definitions: boolean_T, char_T, byte_T, int_T, uint_T, * +// real_T, time_T, ulong_T, ulonglong_T. * +// =========================================================================== +typedef double real_T; +typedef double time_T; +typedef unsigned char boolean_T; +typedef int int_T; +typedef unsigned int uint_T; +typedef unsigned long ulong_T; +typedef unsigned long long ulonglong_T; +typedef char char_T; +typedef unsigned char uchar_T; +typedef char_T byte_T; + +//=======================================================================* +// Min and Max: * +// int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * +// uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * +// ======================================================================= +#define MAX_int8_T ((int8_T)(127)) +#define MIN_int8_T ((int8_T)(-128)) +#define MAX_uint8_T ((uint8_T)(255U)) +#define MAX_int16_T ((int16_T)(32767)) +#define MIN_int16_T ((int16_T)(-32768)) +#define MAX_uint16_T ((uint16_T)(65535U)) +#define MAX_int32_T ((int32_T)(2147483647)) +#define MIN_int32_T ((int32_T)(-2147483647-1)) +#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU)) +#define MAX_int64_T ((int64_T)(9223372036854775807LL)) +#define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) +#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) + +// Block D-Work pointer type +typedef void * pointer_T; + +#endif // RTWTYPES_H + +// +// File trailer for generated code. +// +// [EOF] +// diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/bin/.placeholder.txt b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/bin/.placeholder.txt new file mode 100644 index 0000000000..b0eb8200ba --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/bin/.placeholder.txt @@ -0,0 +1 @@ +.placeholder diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal.startup.strain2.v190.s b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal.startup.strain2.v190.s new file mode 100644 index 0000000000..e9551a1aaf --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal.startup.strain2.v190.s @@ -0,0 +1,415 @@ +;********************** COPYRIGHT(c) 2017 STMicroelectronics ****************** +;* File Name : startup_stm32l443xx.s +;* Author : MCD Application Team +;* Version : V1.3.2 +;* Date : 16-June-2017 +;* Description : STM32L443xx Ultra Low Power devices vector table for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the Cortex-M4 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +;* +;* Redistribution and use in source and binary forms, with or without modification, +;* are permitted provided that the following conditions are met: +;* 1. Redistributions of source code must retain the above copyright notice, +;* this list of conditions and the following disclaimer. +;* 2. Redistributions in binary form must reproduce the above copyright notice, +;* this list of conditions and the following disclaimer in the documentation +;* and/or other materials provided with the distribution. +;* 3. Neither the name of STMicroelectronics nor the names of its contributors +;* may be used to endorse or promote products derived from this software +;* without specific prior written permission. +;* +;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +;* +;******************************************************************************* +; + +; in case of error from assembler, you surely forgot --cpreproc in menu asm-options/misc-controls +; or may also to include it into asm path in menu asm-options/include-paths +;#include "stm32hal_stg.h" + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Stack_Size EQU 0x00003000 +;Stack_Size EQU STM32HAL_STG_STACKSIZE + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Heap_Size EQU 0x00008000 +;Heap_Size EQU STM32HAL_STG_HEAPSIZE + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window WatchDog + DCD PVD_PVM_IRQHandler ; PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection + DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line + DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line + DCD FLASH_IRQHandler ; FLASH + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line0 + DCD EXTI1_IRQHandler ; EXTI Line1 + DCD EXTI2_IRQHandler ; EXTI Line2 + DCD EXTI3_IRQHandler ; EXTI Line3 + DCD EXTI4_IRQHandler ; EXTI Line4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; External Line[9:5]s + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; External Line[15:10] + DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SDMMC1_IRQHandler ; SDMMC1 + DCD 0 ; Reserved + DCD SPI3_IRQHandler ; SPI3 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel 1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel 2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel 3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel 4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel 5 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD COMP_IRQHandler ; COMP Interrupt + DCD LPTIM1_IRQHandler ; LP TIM1 interrupt + DCD LPTIM2_IRQHandler ; LP TIM2 interrupt + DCD USB_IRQHandler ; USB FS + DCD DMA2_Channel6_IRQHandler ; DMA2 Channel 6 + DCD DMA2_Channel7_IRQHandler ; DMA2 Channel 7 + DCD LPUART1_IRQHandler ; LP UART1 interrupt + DCD QUADSPI_IRQHandler ; Quad SPI global interrupt + DCD I2C3_EV_IRQHandler ; I2C3 event + DCD I2C3_ER_IRQHandler ; I2C3 error + DCD SAI1_IRQHandler ; Serial Audio Interface 1 global interrupt + DCD 0 ; Reserved + DCD SWPMI1_IRQHandler ; Serial Wire Interface 1 global interrupt + DCD TSC_IRQHandler ; Touch Sense Controller global interrupt + DCD LCD_IRQHandler ; LCD global interrupt + DCD AES_IRQHandler ; AES global interrupt + DCD RNG_IRQHandler ; RNG global interrupt + DCD FPU_IRQHandler ; FPU + DCD CRS_IRQHandler ; CRS interrupt + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_PVM_IRQHandler [WEAK] + EXPORT TAMP_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT SDMMC1_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT COMP_IRQHandler [WEAK] + EXPORT LPTIM1_IRQHandler [WEAK] + EXPORT LPTIM2_IRQHandler [WEAK] + EXPORT USB_IRQHandler [WEAK] + EXPORT DMA2_Channel6_IRQHandler [WEAK] + EXPORT DMA2_Channel7_IRQHandler [WEAK] + EXPORT LPUART1_IRQHandler [WEAK] + EXPORT QUADSPI_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT SAI1_IRQHandler [WEAK] + EXPORT SWPMI1_IRQHandler [WEAK] + EXPORT TSC_IRQHandler [WEAK] + EXPORT LCD_IRQHandler [WEAK] + EXPORT AES_IRQHandler [WEAK] + EXPORT RNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT CRS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_PVM_IRQHandler +TAMP_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTC_Alarm_IRQHandler +SDMMC1_IRQHandler +SPI3_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +COMP_IRQHandler +LPTIM1_IRQHandler +LPTIM2_IRQHandler +USB_IRQHandler +DMA2_Channel6_IRQHandler +DMA2_Channel7_IRQHandler +LPUART1_IRQHandler +QUADSPI_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +SAI1_IRQHandler +SWPMI1_IRQHandler +TSC_IRQHandler +LCD_IRQHandler +AES_IRQHandler +RNG_IRQHandler +FPU_IRQHandler +CRS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal_stg.h b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal_stg.h new file mode 100644 index 0000000000..a3b9b721d4 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/cfg/stm32hal_stg.h @@ -0,0 +1,54 @@ + + + +// - include guard ---------------------------------------------------------------------------------------------------- +#ifndef __STM32HAL_STG_H_ +#define __STM32HAL_STG_H_ + +#ifdef __cplusplus +extern "C" { +#endif + + + +// -------------------------------------------------------------------------------------------------------------------- +//-------- <<< Use Configuration Wizard in Context Menu >>> ----------------------------------------------------------- +// -------------------------------------------------------------------------------------------------------------------- + + +// STACK & HEAP +// It contains stack and heap size and some externally functions + +// stack size <0x0-0xFFFFFFFF:8> +// define how much stack you want. +#ifndef STM32HAL_STG_STACKSIZE + #define STM32HAL_STG_STACKSIZE 0x00002000 +#endif + +// heap size <0x0-0xFFFFFFFF:8> +// define how much heap you want. +#ifndef STM32HAL_STG_HEAPSIZE + #define STM32HAL_STG_HEAPSIZE 0x00008000 +#endif + +// SYS module + + + + +// -------------------------------------------------------------------------------------------------------------------- +//------------- <<< end of configuration section >>> ------------------------------------------------------------------ +// -------------------------------------------------------------------------------------------------------------------- + + + +#ifdef __cplusplus +} // closing brace for extern "C" +#endif + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.sct b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.sct new file mode 100644 index 0000000000..560088f0a1 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.sct @@ -0,0 +1,40 @@ +;#! armcc -E +; the above must be on teh first line of teh scatter file ... + +; Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia +; Author: Marco Accame +; email: marco.accame@iit.it +; website: www.robotcub.org +; Permission is granted to copy, distribute, and/or modify this program +; under the terms of the GNU General Public License, version 2 or any +; later version published by the Free Software Foundation. +; +; A copy of the license can be found at +; http://www.robotcub.org/icub/license/gpl.txt +; +; This program is distributed in the hope that it will be useful, but +; WITHOUT ANY WARRANTY; without even the implied warranty of +; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General +; Public License for more details +; due to a bug in linker (in some older versions), you may need to put the whole path ... thus change it by hand +;#include "D:\#inhere\sdl\embedded\arm\embody\body\embenv\envcom\eEmemorymap.h" +;#include "..\..\cfg\eEmemorymap.h" + + +; flash starts from xx and its size is xxx +; 80k is: LR_IROM1 0x08000000 0x00014000 { ; load region size_region +; however it was 124K: LR_IROM1 0x08000000 0x0001F000 { ; load region size_region +LR_IROM1 0x08000000 0x0001F000 { ; load region size_region + ER_IROM1 0x08000000 0x0001F000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + RW_IRAM1 0x20000020 0xBFE0 { ; RW data + .ANY (+RW +ZI) + } +} + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvoptx b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvoptx new file mode 100644 index 0000000000..64d6048959 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvoptx @@ -0,0 +1,741 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc; *.md + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + strain2c-btl-v1B0 + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 6 + + + + + + + + + + + STLink\ST-LINKIII-KEIL_SWO.dll + + + + 0 + UL2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ST-LINKIII-KEIL_SWO + -U-O206 -O206 -SF33000 -C0 -A0 -I0 -HNlocalhost -HP7184 -P1 -N00("ARM CoreSight SW-DP (ARM Core") -D00(2BA01477) -L00(0) -TO131090 -TC10000000 -TT10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256.FLM -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + (105=-1,-1,-1,-1,0) + + + + + + 0 + 1 + pp + + + 1 + 1 + info + + + 2 + 1 + type + + + + + 1 + 0 + defInfo32 + 0 + + + + + 2 + 0 + 0x08040000 + 0 + + + + 0 + + + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 0 + 0 + 2 + 33000000 + + + + + + main + 1 + 0 + 0 + 0 + + 1 + 1 + 8 + 0 + 0 + 0 + ../src/main-bootloader.cpp + main-bootloader.cpp + 0 + 0 + + + 1 + 2 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_bootloader.cpp + embot_code_bootloader.cpp + 0 + 0 + + + + + stm32hal + 1 + 0 + 0 + 0 + + 2 + 3 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + stm32hal.strain2c.v1B0.lib + 0 + 0 + + + + + stm32hal-config + 1 + 0 + 0 + 0 + + 3 + 4 + 2 + 0 + 0 + 0 + ..\cfg\stm32hal.startup.strain2.v190.s + stm32hal.startup.strain2.v190.s + 0 + 0 + + + + + rtos + 0 + 0 + 0 + 0 + + 4 + 5 + 4 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + osal.cm4.dbg.lib + 0 + 0 + + + 4 + 6 + 1 + 0 + 0 + 0 + ..\..\..\..\libs\midware\eventviewer\src\eventviewer.c + eventviewer.c + 0 + 0 + + + 4 + 7 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + cmsisos2.lib + 0 + 0 + + + + + embot + 0 + 0 + 0 + 0 + + 5 + 8 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + embot_core.cpp + 0 + 0 + + + 5 + 9 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + embot_app_theBootloader.cpp + 0 + 0 + + + 5 + 10 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + embot_app_theCANboardInfo.cpp + 0 + 0 + + + 5 + 11 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + embot_os.cpp + 0 + 0 + + + 5 + 12 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + embot_os_Task.cpp + 0 + 0 + + + 5 + 13 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + embot_os_theCallbackManager.cpp + 0 + 0 + + + 5 + 14 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + embot_app_theJumper.cpp + 0 + 0 + + + 5 + 15 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + embot_os_theScheduler.cpp + 0 + 0 + + + 5 + 16 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + embot_os_theTimerManager.cpp + 0 + 0 + + + 5 + 17 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + embot_os_Timer.cpp + 0 + 0 + + + 5 + 18 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + embot_app_bootloader_theCANparser.cpp + 0 + 0 + + + 5 + 19 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + embot_prot_can.cpp + 0 + 0 + + + 5 + 20 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + embot_prot_can_bootloader.cpp + 0 + 0 + + + 5 + 21 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + embot_core_binary.cpp + 0 + 0 + + + 5 + 22 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_Action.cpp + embot_os_Action.cpp + 0 + 0 + + + 5 + 23 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + embot_app_theLEDmanager.cpp + 0 + 0 + + + 5 + 24 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_rtos.cpp + embot_os_rtos.cpp + 0 + 0 + + + + + embot-hw + 0 + 0 + 0 + 0 + + 6 + 25 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + embot_hw.cpp + 0 + 0 + + + 6 + 26 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + embot_hw_bsp.cpp + 0 + 0 + + + 6 + 27 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + embot_hw_FlashStorage.cpp + 0 + 0 + + + 6 + 28 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + embot_hw_FlashBurner.cpp + 0 + 0 + + + 6 + 29 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + embot_hw_can.cpp + 0 + 0 + + + 6 + 30 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + embot_hw_sys.cpp + 0 + 0 + + + 6 + 31 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + embot_hw_flash.cpp + 0 + 0 + + + 6 + 32 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + embot_hw_led.cpp + 0 + 0 + + + 6 + 33 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + embot_hw_gpio.cpp + 0 + 0 + + + 6 + 34 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + embot_hw_timer.cpp + 0 + 0 + + + + + embot-hw-lowlevel + 0 + 0 + 0 + 0 + + 7 + 35 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + embot_hw_lowlevel.cpp + 0 + 0 + + + + + embot::hw::bsp + 1 + 0 + 0 + 0 + + 8 + 36 + 8 + 0 + 0 + 0 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + embot_hw_bsp_strain2c.cpp + 0 + 0 + + + + + ::CMSIS + 0 + 0 + 0 + 1 + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvprojx b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvprojx new file mode 100644 index 0000000000..db0ae9cfed --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/proj/strain2c-bootloader-v6.uvprojx @@ -0,0 +1,773 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + strain2c-btl-v1B0 + 0x4 + ARM-ADS + 6180000::V6.18::ARMCLANG + 1 + + + STM32L452RCIx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x00020000) IRAM2(0x10000000,0x00008000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L452RCIx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L452RCIx$CMSIS\SVD\STM32L4x2.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + strain2c_v1B0_bootloader + 1 + 0 + 1 + 1 + 1 + .\lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\Obj\strain2c_v1B0_bootloader.hex ..\bin\strain2c.v1B0.bootloader.hex + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + "" () + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 0 + 0x10000000 + 0x8000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 8 + 1 + 1 + 1 + 0 + 0 + + -Wno-pragma-pack -Wno-deprecated-register + USE_STM32HAL STM32HAL_BOARD_STRAIN2C STM32HAL_DRIVER_V1B0 + + ..\src-plus;..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\api;..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\api;..\..\..\..\..\..\eBcode\arch-arm\embobj\core\exec\multitask;..\..\..\..\..\..\..\..\icub-firmware-shared\eth\embobj\core\core;..\..\..\..\..\..\eBcode\arch-arm\libs\lowlevel\stm32hal\api;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\..\..\eBcode\arch-arm\embot\app;..\..\..\..\..\..\eBcode\arch-arm\embot\i2h;..\..\..\..\..\..\eBcode\arch-arm\embot\hw;..\..\..\..\..\..\eBcode\arch-arm\embot\os;..\..\..\..\..\..\..\..\icub-firmware-shared\can\canProtocolLib;..\..\..\..\embot\app\skeleton;..\..\..\..\embot\prot\can;..\..\bsp + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + .\strain2c-bootloader-v6.sct + + + --diag_suppress=L6329 + + + + + + + + main + + + main-bootloader.cpp + 8 + ../src/main-bootloader.cpp + + + embot_code_bootloader.cpp + 8 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_bootloader.cpp + + + + + stm32hal + + + stm32hal.strain2c.v1B0.lib + 4 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + + + + + stm32hal-config + + + stm32hal.startup.strain2.v190.s + 2 + ..\cfg\stm32hal.startup.strain2.v190.s + + + + + rtos + + + osal.cm4.dbg.lib + 4 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + + + eventviewer.c + 1 + ..\..\..\..\libs\midware\eventviewer\src\eventviewer.c + + + cmsisos2.lib + 4 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + + + + + embot + + + embot_core.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + + + embot_app_theBootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + + + embot_app_theCANboardInfo.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + + + embot_os.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + + + embot_os_Task.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + + + embot_os_theCallbackManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + + + embot_app_theJumper.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + + + embot_os_theScheduler.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + + + embot_os_theTimerManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + + + embot_os_Timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + + + embot_app_bootloader_theCANparser.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + + + embot_prot_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + + + embot_prot_can_bootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + + + embot_core_binary.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + + + embot_os_Action.cpp + 8 + ..\..\..\..\embot\os\embot_os_Action.cpp + + + embot_app_theLEDmanager.cpp + 8 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + + + embot_os_rtos.cpp + 8 + ..\..\..\..\embot\os\embot_os_rtos.cpp + + + + + embot-hw + + + embot_hw.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + + + embot_hw_bsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + + + embot_hw_FlashStorage.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + + + embot_hw_FlashBurner.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + + + embot_hw_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + + + embot_hw_sys.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + + + embot_hw_flash.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + + + embot_hw_led.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + + + embot_hw_gpio.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + + + embot_hw_timer.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + + + + + embot-hw-lowlevel + + + embot_hw_lowlevel.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + + + 2 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 1 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + + + embot::hw::bsp + + + embot_hw_bsp_strain2c.cpp + 8 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + + + + + ::CMSIS + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + strain2c-bootloader-v6 + 0 + 1 + + + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bootloader/src/main-bootloader.cpp b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/src/main-bootloader.cpp new file mode 100644 index 0000000000..e4a15d5191 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bootloader/src/main-bootloader.cpp @@ -0,0 +1,36 @@ + +/* + * Copyright (C) 2019 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + + +#include "embot_app_skeleton_os_bootloader.h" + +// -------------------------------------------------------------------------------------------------------------------- +// bootloader info + +constexpr std::uint8_t defADDRESS = 13; +constexpr embot::app::theCANboardInfo::bootloaderInfo btlInfo +{ + embot::prot::can::Board::strain2c, + embot::prot::can::versionOfBOOTLOADER {2, 6}, + defADDRESS, + "I am a strain2c" +}; + +// -------------------------------------------------------------------------------------------------------------------- + +int main(void) +{ + embot::app::skeleton::os::bootloader::run(btlInfo); + for(;;); +} + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_config.h b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_config.h new file mode 100644 index 0000000000..af50b9cac8 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_config.h @@ -0,0 +1,26 @@ + +/* + * Copyright (C) 2020 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + +// - include guard ---------------------------------------------------------------------------------------------------- + +#ifndef _EMBOT_HW_BSP_CONFIG_H_ +#define _EMBOT_HW_BSP_CONFIG_H_ + + +#if defined(STM32HAL_BOARD_STRAIN2C) + #include "embot_hw_bsp_strain2c_config.h" +#else + #error wrong board +#endif + + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c.cpp b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c.cpp new file mode 100644 index 0000000000..ba012b149f --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c.cpp @@ -0,0 +1,866 @@ + +/* + * Copyright (C) 2020 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + + +// -------------------------------------------------------------------------------------------------------------------- +// - public interface +// -------------------------------------------------------------------------------------------------------------------- + +#include "embot_hw_bsp.h" + + +// -------------------------------------------------------------------------------------------------------------------- +// - external dependencies +// -------------------------------------------------------------------------------------------------------------------- + +#include +#include +#include + +#include "embot_core_binary.h" +#include "embot_core.h" + +#if defined(USE_STM32HAL) + #include "stm32hal.h" +#else + #warning this implementation is only for stm32hal +#endif + + +#if defined(STM32HAL_BOARD_STRAIN2C) +#else + #error this file is only for STM32HAL_BOARD_STRAIN2C +#endif + + +using namespace std; +using namespace embot::core::binary; + +// -------------------------------------------------------------------------------------------------------------------- +// - configuration of peripherals and chips. it is done board by board. it contains a check vs correct STM32HAL_BOARD_* +// -------------------------------------------------------------------------------------------------------------------- + +#include "embot_hw_bsp_strain2c_config.h" + + +// -------------------------------------------------------------------------------------------------------------------- +// - specialize the bsp +// -------------------------------------------------------------------------------------------------------------------- + +#if !defined(EMBOT_ENABLE_hw_bsp_specialize) +bool embot::hw::bsp::specialize() { return true; } +#else +bool embot::hw::bsp::specialize() { return true; } +#endif //EMBOT_ENABLE_hw_bsp_specialize + + +// -------------------------------------------------------------------------------------------------------------------- +// - support maps +// -------------------------------------------------------------------------------------------------------------------- + + + +// - support map: begin of embot::hw::gpio + +#include "embot_hw_gpio_bsp.h" + +#if !defined(HAL_GPIO_MODULE_ENABLED) || !defined(EMBOT_ENABLE_hw_gpio) + #error CAVEAT: embot::hw requires GPIO. pls enable it! +#else + +namespace embot { namespace hw { namespace gpio { + + #if defined(STM32HAL_BOARD_STRAIN2C) + const BSP thebsp { + // supportmask2d + {{ + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff + }}, + // ports + {{ + GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, nullptr, nullptr, nullptr + }}, + {{ + [](){__HAL_RCC_GPIOA_CLK_ENABLE();}, [](){__HAL_RCC_GPIOB_CLK_ENABLE();}, + [](){__HAL_RCC_GPIOC_CLK_ENABLE();}, [](){__HAL_RCC_GPIOD_CLK_ENABLE();}, + [](){__HAL_RCC_GPIOE_CLK_ENABLE();}, nullptr, + nullptr, nullptr + }} + }; + #else + #error embot::hw::gpio::thebsp must be defined + #endif + + void BSP::init(embot::hw::GPIO h) const {} + + const BSP& getBSP() + { + return thebsp; + } + +}}} // namespace embot { namespace hw { namespace gpio { + +#endif // gpio + +// - support map: end of embot::hw::gpio + + + +// - support map: begin of embot::hw::led + +#include "embot_hw_led_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_led) + +namespace embot { namespace hw { namespace led { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::LED h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace led { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP led1p = { .on = embot::hw::gpio::State::RESET, .off = embot::hw::gpio::State::SET, .gpio = {embot::hw::GPIO::PORT::B, embot::hw::GPIO::PIN::eleven} }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(LED::one), + // properties + {{ + &led1p, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr + }} + }; + + void BSP::init(embot::hw::LED h) const {} + + #else + #error embot::hw::led::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } + +}}} // namespace embot { namespace hw { namespace led { + +#endif // led + +// - support map: end of embot::hw::led + + + +// - support map: begin of embot::hw::button + +#include "embot_hw_button_bsp.h" + + +#if !defined(EMBOT_ENABLE_hw_button) + +namespace embot { namespace hw { namespace button { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::BTN h) const {} + void BSP::onEXTI(const embot::hw::gpio::PROP &p) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else +#endif // button + +// - support map: end of embot::hw::button + + + +// - support map: begin of embot::hw::can + +#include "embot_hw_can_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_can) + +namespace embot { namespace hw { namespace can { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::CAN h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace can { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP can1p = { .handle = &hcan1 }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(CAN::one), + // properties + {{ + &can1p + }} + }; + + void BSP::init(embot::hw::CAN h) const + { + if(h == CAN::one) + { + MX_CAN1_Init(); + } + } + + #else + #error embot::hw::can::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } + +}}} // namespace embot { namespace hw { namespace can { + + +#if defined(HAL_CAN_MODULE_ENABLED) + +// irq handlers for can: they are common to every board which has can + +void CAN1_TX_IRQHandler(void) +{ + HAL_CAN_IRQHandler(&hcan1); +} + +void CAN1_RX0_IRQHandler(void) +{ + HAL_CAN_IRQHandler(&hcan1); +} +#endif // + +#endif // EMBOT_ENABLE_hw_can + + +// - support map: end of embot::hw::can + + + +// - support map: begin of embot::hw::flash + +#include "embot_hw_flash_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_flash) + +namespace embot { namespace hw { namespace flash { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::FLASH h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}}} + +#else + +namespace embot { namespace hw { namespace flash { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + #if defined(STRAIN2_APP_AT_128K) + + // strain legacy: application @ 128k and application storage together with sharedstorage + constexpr PROP whole {{0x08000000, (256)*1024, 2*1024}}; + constexpr PROP bootloader {{0x08000000, (124)*1024, 2*1024}}; // bootloader + constexpr PROP sharedstorage {{0x08000000+(124*1024), (4)*1024, 2*1024}}; // sharedstorage: on top of bootloader + constexpr PROP applicationstorage {{0x08000000+(124*1024), (4)*1024, 2*1024}}; // applicationstorage: together with sharedstorage + constexpr PROP application {{0x08000000+(128*1024), (128)*1024, 2*1024}}; // application @ 128k + + #else + + // strain2: application @ 080k + constexpr PROP whole {{0x08000000, (256)*1024, 2*1024}}; + constexpr PROP bootloader {{0x08000000, (78)*1024, 2*1024}}; // bootloader + constexpr PROP sharedstorage {{0x08000000+(78*1024), (2)*1024, 2*1024}}; // sharedstorage: on top of bootloader + constexpr PROP application {{0x08000000+(80*1024), (172)*1024, 2*1024}}; // application @ 080k + constexpr PROP applicationstorage {{0x08000000+(252*1024), (4)*1024, 2*1024}}; // applicationstorage: on top of application + + #endif + + #else + #error embot::hw::flash::thebsp must be defined + #endif + + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(FLASH::whole) | mask::pos2mask(FLASH::bootloader) | mask::pos2mask(FLASH::application) | + mask::pos2mask(FLASH::sharedstorage) | mask::pos2mask(FLASH::applicationstorage), + // properties + {{ + &whole, &bootloader, &application, &sharedstorage, &applicationstorage + }} + }; + + void BSP::init(embot::hw::FLASH h) const {} + + const BSP& getBSP() + { + return thebsp; + } + +}}} // namespace embot { namespace hw { namespace flash { + +#endif // flash + +// - support map: end of embot::hw::flash + + + +// - support map: begin of embot::hw::pga308 + +#include "embot_hw_pga308_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_pga308) + +namespace embot { namespace hw { namespace pga308 { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::PGA308 h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace pga308 { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP prop { .poweron = {embot::hw::GPIO::PORT::B, embot::hw::GPIO::PIN::fifteen} }; // EN_2V8_GPIO_Port, EN_2V8_Pin + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(PGA308::one) | mask::pos2mask(PGA308::two) | mask::pos2mask(PGA308::three) | + mask::pos2mask(PGA308::four) | mask::pos2mask(PGA308::five) | mask::pos2mask(PGA308::six), + // properties + {{ + &prop, &prop, &prop, &prop, &prop, &prop + }} + }; + + void BSP::init(embot::hw::PGA308 h) const {} + + #else + #error embot::hw::pga308::thebsp must be defined + #endif + + + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#endif + + +// - support map: end of embot::hw::pga308 + + + +// - support map: begin of embot::hw::si7051 + +#include "embot_hw_si7051_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_si7051) + +namespace embot { namespace hw { namespace si7051 { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::SI7051 h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +#include "embot_hw_sys.h" + +namespace embot { namespace hw { namespace si7051 { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + // actually the strain2 has another chip mounted, which is in the same i2c bus as the bno. + // added support for second sensor D.T. + constexpr PROP prop01 { embot::hw::i2c::Descriptor{embot::hw::I2C::one, 0x80} }; + constexpr PROP prop02 { embot::hw::i2c::Descriptor{embot::hw::I2C::two, 0x80} }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(SI7051::one)| mask::pos2mask(SI7051::two), + // properties + {{ + &prop01, &prop02 + }} + }; + + void BSP::init(embot::hw::SI7051 h) const { } + #else + #error embot::hw::can::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } +}}} + + +#endif // si7051 + + +// - support map: end of embot::hw::si7051 + + +// - support map: begin of embot::hw::onewire + +#include "embot_hw_onewire_bsp.h" + +#if !defined(EMBOT_ENABLE_hw_onewire) + +namespace embot { namespace hw { namespace onewire { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::ONEWIRE h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace onewire { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP onewi1 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::four} }; // W_STRAIN1_GPIO_Port, W_STRAIN1_Pin + constexpr PROP onewi2 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::five} }; // W_STRAIN2_GPIO_Port, W_STRAIN2_Pin + constexpr PROP onewi3 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::six} }; // W_STRAIN3_GPIO_Port, W_STRAIN3_Pin + constexpr PROP onewi4 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::seven} }; // W_STRAIN4_GPIO_Port, W_STRAIN4_Pin + constexpr PROP onewi5 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::eight} }; // W_STRAIN5_GPIO_Port, W_STRAIN5_Pin + constexpr PROP onewi6 { .gpio = { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::nine} }; // W_STRAIN6_GPIO_Port, W_STRAIN6_Pin + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(ONEWIRE::one) | mask::pos2mask(ONEWIRE::two) | mask::pos2mask(ONEWIRE::three) | + mask::pos2mask(ONEWIRE::four) | mask::pos2mask(ONEWIRE::five) | mask::pos2mask(ONEWIRE::six), + // properties + {{ + &onewi1, &onewi2, &onewi3, &onewi4, &onewi5, &onewi6 + }} + }; + + void BSP::init(embot::hw::ONEWIRE h) const {} + + #else + #error embot::hw::onewire::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#endif + +// - support map: end of embot::hw::onewire + + + +// - support map: begin of embot::hw::adc + +#include "embot_hw_adc_bsp.h" + +#if !defined(HAL_ADC_MODULE_ENABLED) || !defined(EMBOT_ENABLE_hw_adc) + +namespace embot { namespace hw { namespace adc { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::ADC h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace adc { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP adc1p { .handle = &hadc1 }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(ADC::one), + // properties + {{ + &adc1p + }} + }; + + void BSP::init(embot::hw::ADC h) const + { + // init peripherals: adc1 and dma1 + MX_ADC1_Init(); + // dma is globally initted by stm32hal_bsp_init() because it holds all dma peripherals + //MX_DMA_Init(); + } + + #else + #error embot::hw::bsp::adc::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } + +}}} + + +#if defined(STM32HAL_BOARD_STRAIN2C) + +void DMA1_Channel1_IRQHandler(void) +{ + HAL_DMA_IRQHandler(&hdma_adc1); +} + +// this IRQHandler is not used if we have DMA .... +//void ADC1_IRQHandler(void) +//{ +// HAL_ADC_IRQHandler(&hadc1); +//} + +#endif + +#endif // adc + +// - support map: end of embot::hw::adc + + + +// - support map: begin of embot::hw::timer + +#include "embot_hw_timer_bsp.h" + +#if !defined(HAL_TIM_MODULE_ENABLED) || !defined(EMBOT_ENABLE_hw_timer) + +namespace embot { namespace hw { namespace timer { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::TIMER h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace timer { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + // sadly we cannot use constexpr because of the reinterpret_cast<> inside TIM6 etc. + static const PROP tim06p = { .TIMx = TIM6, .handle = &htim6, .clock = embot::hw::CLOCK::syscore, .isonepulse = false, .mastermode = true }; +// static const PROP tim07p = { .TIMx = TIM7, .handle = &htim7, .clock = embot::hw::CLOCK::syscore, .isonepulse = false, .mastermode = true }; + static const PROP tim15p = { .TIMx = TIM15, .handle = &htim15, .clock = embot::hw::CLOCK::syscore, .isonepulse = true, .mastermode = false }; + static const PROP tim16p = { .TIMx = TIM16, .handle = &htim16, .clock = embot::hw::CLOCK::syscore, .isonepulse = false, .mastermode = false }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(TIMER::six) | mask::pos2mask(TIMER::seven) | + mask::pos2mask(TIMER::fifteen) | mask::pos2mask(TIMER::sixteen), + // properties + {{ + nullptr, nullptr, nullptr, nullptr, nullptr, &tim06p, nullptr, nullptr, // from 1 to 8 + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &tim15p, &tim16p // from 9 to 16 + }} + }; + + void BSP::init(embot::hw::TIMER h) const {} + + #else + #error embot::hw::timer::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } +}}} + +// in here it is implemented in the way the good old hal2 was doing: the handler directly manages the callback +// instead the stm hal make a lot of calls before actually calling the callback code, hence it is slower. + +#include "embot_hw_timer.h" + +void manageInterrupt(embot::hw::TIMER t, TIM_HandleTypeDef *htim) +{ + if(__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) + { + if(__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) !=RESET) + { + __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); + embot::hw::timer::execute(t); + } + } +} + +#define STM32HAL_HAS_TIM6 +//#define STM32HAL_HAS_TIM7 +#define STM32HAL_HAS_TIM15 +#define STM32HAL_HAS_TIM16 + +#if defined(STM32HAL_HAS_TIM6) +void TIM6_DAC_IRQHandler(void) +{ + manageInterrupt(embot::hw::TIMER::six, &htim6); +} +#endif + +//#if defined(STM32HAL_HAS_TIM7) +//void TIM7_IRQHandler(void) +//{ +// manageInterrupt(embot::hw::TIMER::seven, &htim7); +//} +//#endif + +#if defined(STM32HAL_HAS_TIM15) +void TIM1_BRK_TIM15_IRQHandler(void) +{ + manageInterrupt(embot::hw::TIMER::fifteen, &htim15); +} +#endif + +#if defined(STM32HAL_HAS_TIM16) +void TIM1_UP_TIM16_IRQHandler(void) +{ + manageInterrupt(embot::hw::TIMER::sixteen, &htim16); +} +#endif + +#endif // timer + + +// - support map: end of embot::hw::timer + + +// - support map: begin of embot::hw::i2c + +#include "embot_hw_i2c_bsp.h" + + +#if !defined(HAL_I2C_MODULE_ENABLED) || !defined(EMBOT_ENABLE_hw_i2c) + +namespace embot { namespace hw { namespace i2c { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::I2C h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace i2c { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + constexpr PROP i2c1p { &hi2c1, embot::hw::i2c::Speed::fast400 }; + constexpr PROP i2c2p { &hi2c2, embot::hw::i2c::Speed::fast400 }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(I2C::one) | mask::pos2mask(I2C::two), + // properties + {{ + &i2c1p, &i2c2p, nullptr + }} + }; + + void BSP::init(embot::hw::I2C h) const + { + if(h == I2C::one) + { + MX_I2C1_Init(); + } + else if(h == I2C::two) + { + MX_I2C2_Init(); + } + } + + #else + #error embot::hw::i2c::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } + +}}} // namespace embot { namespace hw { namespace i2c { + + +// irq handlers of i2c + +#if defined(STM32HAL_BOARD_MTB4) | defined(STM32HAL_BOARD_STRAIN2C) | defined(STM32HAL_BOARD_RFE) + +void I2C1_EV_IRQHandler(void) +{ + HAL_I2C_EV_IRQHandler(&hi2c1); +} + +void I2C1_ER_IRQHandler(void) +{ + HAL_I2C_ER_IRQHandler(&hi2c1); +} + +void DMA1_Channel6_IRQHandler(void) +{ + HAL_DMA_IRQHandler(&hdma_i2c1_tx); +} + +void DMA1_Channel7_IRQHandler(void) +{ + HAL_DMA_IRQHandler(&hdma_i2c1_rx); +} + +void DMA1_Channel4_IRQHandler(void) +{ + HAL_DMA_IRQHandler(&hdma_i2c2_tx); +} + +void DMA1_Channel5_IRQHandler(void) +{ + HAL_DMA_IRQHandler(&hdma_i2c2_rx); +} + +void I2C2_EV_IRQHandler(void) +{ + HAL_I2C_EV_IRQHandler(&hi2c2); +} + +void I2C2_ER_IRQHandler(void) +{ + HAL_I2C_ER_IRQHandler(&hi2c2); +} + + +#endif // irq handlers + +#endif // i2c + +// - support map: end of embot::hw::i2c + + + +// - support map: begin of embot::hw::bno055 + +#include "embot_hw_bno055_bsp.h" + +#if !defined(HAL_I2C_MODULE_ENABLED) || !defined(EMBOT_ENABLE_hw_bno055) + +namespace embot { namespace hw { namespace bno055 { + + constexpr BSP thebsp { }; + void BSP::init(embot::hw::BNO055 h) const {} + const BSP& getBSP() + { + return thebsp; + } + +}}} + +#else + +namespace embot { namespace hw { namespace bno055 { + + #if defined(STM32HAL_BOARD_STRAIN2C) + + // .boot = { BNO055_BOOT_GPIO_Port, BNO055_BOOT_Pin }, .reset = { BNO055_RESET_GPIO_Port, BNO055_RESET_Pin } + constexpr PROP prop01 { + { embot::hw::I2C::two, 0x52 }, + { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::thirteen }, // .boot + { embot::hw::GPIO::PORT::C, embot::hw::GPIO::PIN::twelve } // .reset + }; + + constexpr BSP thebsp { + // maskofsupported + mask::pos2mask(BNO055::one), + // properties + {{ + &prop01 + }} + }; + + void BSP::init(embot::hw::BNO055 h) const {} + #else + #error embot::hw::bno055::thebsp must be defined + #endif + + const BSP& getBSP() + { + return thebsp; + } +}}} + +#endif // bno055 + +// - support map: end of embot::hw::bno055 + + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c_config.h b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c_config.h new file mode 100644 index 0000000000..59e41203d3 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/bsp/embot_hw_bsp_strain2c_config.h @@ -0,0 +1,39 @@ + +/* + * Copyright (C) 2020 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + +// - include guard ---------------------------------------------------------------------------------------------------- + +#ifndef _EMBOT_HW_BSP_STRAIN2C_CONFIG_H_ +#define _EMBOT_HW_BSP_STRAIN2C_CONFIG_H_ + + +#if defined(STM32HAL_BOARD_STRAIN2C) + + #undef EMBOT_ENABLE_hw_bsp_specialize + #define EMBOT_ENABLE_hw_gpio + #define EMBOT_ENABLE_hw_led + #define EMBOT_ENABLE_hw_can + #define EMBOT_ENABLE_hw_flash + #define EMBOT_ENABLE_hw_pga308 + #define EMBOT_ENABLE_hw_adc + #define EMBOT_ENABLE_hw_onewire + #define EMBOT_ENABLE_hw_timer + #define EMBOT_ENABLE_hw_si7051 + #define EMBOT_ENABLE_hw_i2c + #define EMBOT_ENABLE_hw_bno055 + +#else + #error this is the bsp config of STM32HAL_BOARD_STRAIN2 ... +#endif + + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/bin/.placeholder.txt b/emBODY/eBcode/arch-arm/board/strain2c/test/bin/.placeholder.txt new file mode 100644 index 0000000000..b0eb8200ba --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/bin/.placeholder.txt @@ -0,0 +1 @@ +.placeholder diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal.startup.strain2.v190.s b/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal.startup.strain2.v190.s new file mode 100644 index 0000000000..e9551a1aaf --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal.startup.strain2.v190.s @@ -0,0 +1,415 @@ +;********************** COPYRIGHT(c) 2017 STMicroelectronics ****************** +;* File Name : startup_stm32l443xx.s +;* Author : MCD Application Team +;* Version : V1.3.2 +;* Date : 16-June-2017 +;* Description : STM32L443xx Ultra Low Power devices vector table for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the Cortex-M4 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +;* +;* Redistribution and use in source and binary forms, with or without modification, +;* are permitted provided that the following conditions are met: +;* 1. Redistributions of source code must retain the above copyright notice, +;* this list of conditions and the following disclaimer. +;* 2. Redistributions in binary form must reproduce the above copyright notice, +;* this list of conditions and the following disclaimer in the documentation +;* and/or other materials provided with the distribution. +;* 3. Neither the name of STMicroelectronics nor the names of its contributors +;* may be used to endorse or promote products derived from this software +;* without specific prior written permission. +;* +;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +;* +;******************************************************************************* +; + +; in case of error from assembler, you surely forgot --cpreproc in menu asm-options/misc-controls +; or may also to include it into asm path in menu asm-options/include-paths +;#include "stm32hal_stg.h" + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Stack_Size EQU 0x00003000 +;Stack_Size EQU STM32HAL_STG_STACKSIZE + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Heap_Size EQU 0x00008000 +;Heap_Size EQU STM32HAL_STG_HEAPSIZE + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window WatchDog + DCD PVD_PVM_IRQHandler ; PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection + DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line + DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line + DCD FLASH_IRQHandler ; FLASH + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line0 + DCD EXTI1_IRQHandler ; EXTI Line1 + DCD EXTI2_IRQHandler ; EXTI Line2 + DCD EXTI3_IRQHandler ; EXTI Line3 + DCD EXTI4_IRQHandler ; EXTI Line4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; External Line[9:5]s + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; External Line[15:10] + DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SDMMC1_IRQHandler ; SDMMC1 + DCD 0 ; Reserved + DCD SPI3_IRQHandler ; SPI3 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel 1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel 2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel 3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel 4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel 5 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD COMP_IRQHandler ; COMP Interrupt + DCD LPTIM1_IRQHandler ; LP TIM1 interrupt + DCD LPTIM2_IRQHandler ; LP TIM2 interrupt + DCD USB_IRQHandler ; USB FS + DCD DMA2_Channel6_IRQHandler ; DMA2 Channel 6 + DCD DMA2_Channel7_IRQHandler ; DMA2 Channel 7 + DCD LPUART1_IRQHandler ; LP UART1 interrupt + DCD QUADSPI_IRQHandler ; Quad SPI global interrupt + DCD I2C3_EV_IRQHandler ; I2C3 event + DCD I2C3_ER_IRQHandler ; I2C3 error + DCD SAI1_IRQHandler ; Serial Audio Interface 1 global interrupt + DCD 0 ; Reserved + DCD SWPMI1_IRQHandler ; Serial Wire Interface 1 global interrupt + DCD TSC_IRQHandler ; Touch Sense Controller global interrupt + DCD LCD_IRQHandler ; LCD global interrupt + DCD AES_IRQHandler ; AES global interrupt + DCD RNG_IRQHandler ; RNG global interrupt + DCD FPU_IRQHandler ; FPU + DCD CRS_IRQHandler ; CRS interrupt + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_PVM_IRQHandler [WEAK] + EXPORT TAMP_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT SDMMC1_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT COMP_IRQHandler [WEAK] + EXPORT LPTIM1_IRQHandler [WEAK] + EXPORT LPTIM2_IRQHandler [WEAK] + EXPORT USB_IRQHandler [WEAK] + EXPORT DMA2_Channel6_IRQHandler [WEAK] + EXPORT DMA2_Channel7_IRQHandler [WEAK] + EXPORT LPUART1_IRQHandler [WEAK] + EXPORT QUADSPI_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT SAI1_IRQHandler [WEAK] + EXPORT SWPMI1_IRQHandler [WEAK] + EXPORT TSC_IRQHandler [WEAK] + EXPORT LCD_IRQHandler [WEAK] + EXPORT AES_IRQHandler [WEAK] + EXPORT RNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT CRS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_PVM_IRQHandler +TAMP_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTC_Alarm_IRQHandler +SDMMC1_IRQHandler +SPI3_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +COMP_IRQHandler +LPTIM1_IRQHandler +LPTIM2_IRQHandler +USB_IRQHandler +DMA2_Channel6_IRQHandler +DMA2_Channel7_IRQHandler +LPUART1_IRQHandler +QUADSPI_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +SAI1_IRQHandler +SWPMI1_IRQHandler +TSC_IRQHandler +LCD_IRQHandler +AES_IRQHandler +RNG_IRQHandler +FPU_IRQHandler +CRS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal_stg.h b/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal_stg.h new file mode 100644 index 0000000000..a3b9b721d4 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/cfg/stm32hal_stg.h @@ -0,0 +1,54 @@ + + + +// - include guard ---------------------------------------------------------------------------------------------------- +#ifndef __STM32HAL_STG_H_ +#define __STM32HAL_STG_H_ + +#ifdef __cplusplus +extern "C" { +#endif + + + +// -------------------------------------------------------------------------------------------------------------------- +//-------- <<< Use Configuration Wizard in Context Menu >>> ----------------------------------------------------------- +// -------------------------------------------------------------------------------------------------------------------- + + +// STACK & HEAP +// It contains stack and heap size and some externally functions + +// stack size <0x0-0xFFFFFFFF:8> +// define how much stack you want. +#ifndef STM32HAL_STG_STACKSIZE + #define STM32HAL_STG_STACKSIZE 0x00002000 +#endif + +// heap size <0x0-0xFFFFFFFF:8> +// define how much heap you want. +#ifndef STM32HAL_STG_HEAPSIZE + #define STM32HAL_STG_HEAPSIZE 0x00008000 +#endif + +// SYS module + + + + +// -------------------------------------------------------------------------------------------------------------------- +//------------- <<< end of configuration section >>> ------------------------------------------------------------------ +// -------------------------------------------------------------------------------------------------------------------- + + + +#ifdef __cplusplus +} // closing brace for extern "C" +#endif + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.sct b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.sct new file mode 100644 index 0000000000..ae6c19a746 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.sct @@ -0,0 +1,40 @@ +;#! armcc -E +; the above must be on teh first line of teh scatter file ... + +; Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia +; Author: Marco Accame +; email: marco.accame@iit.it +; website: www.robotcub.org +; Permission is granted to copy, distribute, and/or modify this program +; under the terms of the GNU General Public License, version 2 or any +; later version published by the Free Software Foundation. +; +; A copy of the license can be found at +; http://www.robotcub.org/icub/license/gpl.txt +; +; This program is distributed in the hope that it will be useful, but +; WITHOUT ANY WARRANTY; without even the implied warranty of +; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General +; Public License for more details +; due to a bug in linker (in some older versions), you may need to put the whole path ... thus change it by hand +;#include "D:\#inhere\sdl\embedded\arm\embody\body\embenv\envcom\eEmemorymap.h" +;#include "..\..\cfg\eEmemorymap.h" + + +; flash starts from xx and its size is xxx +; 80k is: LR_IROM1 0x08000000 0x00014000 { ; load region size_region +; however it was 124K: LR_IROM1 0x08000000 0x0001F000 { ; load region size_region +LR_IROM1 0x08000000 0x00013800 { ; load region size_region + ER_IROM1 0x08000000 0x00013800 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + RW_IRAM1 0x20000020 0xBFE0 { ; RW data + .ANY (+RW +ZI) + } +} + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvoptx b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvoptx new file mode 100644 index 0000000000..0930c8b4cb --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvoptx @@ -0,0 +1,858 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc; *.md + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + strain2c-test-v1B0 + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 6 + + + + + + + + + + + STLink\ST-LINKIII-KEIL_SWO.dll + + + + 0 + UL2CM3 + -UAny -O206 -S0 -C0 -P00 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO65554 -TC10000000 -TT10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO31 -FN1 -FC1000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ST-LINKIII-KEIL_SWO + -UAny -O206 -SF10000 -C0 -A0 -I0 -HNlocalhost -HP7184 -P1 -N00("ARM CoreSight SW-DP (ARM Core") -D00(2BA01477) -L00(0) -TO65554 -TC10000000 -TT10000000 -TP21 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO31 -FD20000000 -FC1000 -FN1 -FF0STM32L4xx_256.FLM -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + (105=-1,-1,-1,-1,0) + + + + + 0 + 0 + 463 + 1 +
134254832
+ 0 + 0 + 0 + 0 + 0 + 1 + ..\src\embot_code_bootloader-for-test.cpp + + \\strain2_revC_test_v1B0\../src/embot_code_bootloader-for-test.cpp\463 +
+ + 1 + 0 + 26 + 1 +
134257158
+ 0 + 0 + 0 + 0 + 0 + 1 + ../src/main-bootloader.cpp + + \\strain2_revC_test_v1B0\../src/main-bootloader.cpp\26 +
+
+ + + 0 + 1 + pp + + + 1 + 1 + info + + + 2 + 1 + type + + + + + 1 + 0 + defInfo32 + 0 + + + + + 2 + 0 + 0x08040000 + 0 + + + + 0 + + + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 0 + 0 + 2 + 10000000 + +
+
+ + + main + 1 + 0 + 0 + 0 + + 1 + 1 + 8 + 0 + 0 + 0 + ../src/main-bootloader.cpp + main-bootloader.cpp + 0 + 0 + + + 1 + 2 + 8 + 0 + 0 + 0 + ..\src\embot_code_bootloader-for-test.cpp + embot_code_bootloader-for-test.cpp + 0 + 0 + + + + + stm32hal + 1 + 0 + 0 + 0 + + 2 + 3 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + stm32hal.strain2c.v1B0.lib + 0 + 0 + + + + + stm32hal-config + 1 + 0 + 0 + 0 + + 3 + 4 + 2 + 0 + 0 + 0 + ..\cfg\stm32hal.startup.strain2.v190.s + stm32hal.startup.strain2.v190.s + 0 + 0 + + + + + rtos + 1 + 0 + 0 + 0 + + 4 + 5 + 4 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + osal.cm4.dbg.lib + 0 + 0 + + + 4 + 6 + 1 + 0 + 0 + 0 + ..\..\..\..\libs\midware\eventviewer\src\eventviewer.c + eventviewer.c + 0 + 0 + + + 4 + 7 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + cmsisos2.lib + 0 + 0 + + + + + embot + 1 + 0 + 0 + 0 + + 5 + 8 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + embot_core.cpp + 0 + 0 + + + 5 + 9 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + embot_app_theBootloader.cpp + 0 + 0 + + + 5 + 10 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + embot_app_theCANboardInfo.cpp + 0 + 0 + + + 5 + 11 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + embot_os.cpp + 0 + 0 + + + 5 + 12 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + embot_os_Task.cpp + 0 + 0 + + + 5 + 13 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + embot_os_theCallbackManager.cpp + 0 + 0 + + + 5 + 14 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + embot_app_theJumper.cpp + 0 + 0 + + + 5 + 15 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + embot_os_theScheduler.cpp + 0 + 0 + + + 5 + 16 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + embot_os_theTimerManager.cpp + 0 + 0 + + + 5 + 17 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + embot_os_Timer.cpp + 0 + 0 + + + 5 + 18 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + embot_app_bootloader_theCANparser.cpp + 0 + 0 + + + 5 + 19 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + embot_prot_can.cpp + 0 + 0 + + + 5 + 20 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + embot_prot_can_bootloader.cpp + 0 + 0 + + + 5 + 21 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + embot_core_binary.cpp + 0 + 0 + + + 5 + 22 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_Action.cpp + embot_os_Action.cpp + 0 + 0 + + + 5 + 23 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + embot_app_theLEDmanager.cpp + 0 + 0 + + + 5 + 24 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_rtos.cpp + embot_os_rtos.cpp + 0 + 0 + + + 5 + 25 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\prot\can\embot_prot_can_analog_polling.cpp + embot_prot_can_analog_polling.cpp + 0 + 0 + + + + + embot-hw + 1 + 0 + 0 + 0 + + 6 + 26 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + embot_hw.cpp + 0 + 0 + + + 6 + 27 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + embot_hw_bsp.cpp + 0 + 0 + + + 6 + 28 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + embot_hw_FlashStorage.cpp + 0 + 0 + + + 6 + 29 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + embot_hw_FlashBurner.cpp + 0 + 0 + + + 6 + 30 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + embot_hw_can.cpp + 0 + 0 + + + 6 + 31 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + embot_hw_sys.cpp + 0 + 0 + + + 6 + 32 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + embot_hw_flash.cpp + 0 + 0 + + + 6 + 33 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + embot_hw_led.cpp + 0 + 0 + + + 6 + 34 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + embot_hw_gpio.cpp + 0 + 0 + + + 6 + 35 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + embot_hw_timer.cpp + 0 + 0 + + + 6 + 36 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_bno055.cpp + embot_hw_bno055.cpp + 0 + 0 + + + 6 + 37 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_si7051.cpp + embot_hw_si7051.cpp + 0 + 0 + + + 6 + 38 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_i2c.cpp + embot_hw_i2c.cpp + 0 + 0 + + + 6 + 39 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_pga308.cpp + embot_hw_pga308.cpp + 0 + 0 + + + 6 + 40 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_onewire.cpp + embot_hw_onewire.cpp + 0 + 0 + + + 6 + 41 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_adc.cpp + embot_hw_adc.cpp + 0 + 0 + + + + + embot-hw-lowlevel + 1 + 0 + 0 + 0 + + 7 + 42 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + embot_hw_lowlevel.cpp + 0 + 0 + + + + + embot::hw::bsp + 1 + 0 + 0 + 0 + + 8 + 43 + 8 + 0 + 0 + 0 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + embot_hw_bsp_strain2c.cpp + 0 + 0 + + + + + ::CMSIS + 0 + 0 + 0 + 1 + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvprojx b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvprojx new file mode 100644 index 0000000000..7125363c80 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test-v6.uvprojx @@ -0,0 +1,798 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + strain2c-test-v1B0 + 0x4 + ARM-ADS + 6180000::V6.18::ARMCLANG + 1 + + + STM32L452RCIx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x00020000) IRAM2(0x10000000,0x00008000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L452RCIx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L452RCIx$CMSIS\SVD\STM32L4x2.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + strain2_revC_test_v1B0 + 1 + 0 + 1 + 1 + 1 + .\lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\Obj\strain2_revC_test_v1B0.hex ..\bin\strain2_revC_test_v1B0.hex + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + "" () + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 0 + 0x10000000 + 0x8000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 8 + 1 + 1 + 1 + 0 + 0 + + -Wno-pragma-pack -Wno-deprecated-register + USE_STM32HAL STM32HAL_BOARD_STRAIN2C STM32HAL_DRIVER_V1B0 + + ..\src-plus;..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\api;..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\api;..\..\..\..\..\..\eBcode\arch-arm\embobj\core\exec\multitask;..\..\..\..\..\..\..\..\icub-firmware-shared\eth\embobj\core\core;..\..\..\..\..\..\eBcode\arch-arm\libs\lowlevel\stm32hal\api;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\..\..\eBcode\arch-arm\embot\app;..\..\..\..\..\..\eBcode\arch-arm\embot\i2h;..\..\..\..\..\..\eBcode\arch-arm\embot\hw;..\..\..\..\..\..\eBcode\arch-arm\embot\os;..\..\..\..\..\..\..\..\icub-firmware-shared\can\canProtocolLib;..\..\..\..\embot\app\skeleton;..\..\..\..\embot\prot\can;..\..\bsp;..\..\..\..\embot\app\dsp + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + .\strain2c-test-v6.sct + + + --diag_suppress=L6329 + + + + + + + + main + + + main-bootloader.cpp + 8 + ../src/main-bootloader.cpp + + + embot_code_bootloader-for-test.cpp + 8 + ..\src\embot_code_bootloader-for-test.cpp + + + + + stm32hal + + + stm32hal.strain2c.v1B0.lib + 4 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + + + + + stm32hal-config + + + stm32hal.startup.strain2.v190.s + 2 + ..\cfg\stm32hal.startup.strain2.v190.s + + + + + rtos + + + osal.cm4.dbg.lib + 4 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + + + eventviewer.c + 1 + ..\..\..\..\libs\midware\eventviewer\src\eventviewer.c + + + cmsisos2.lib + 4 + ..\..\..\..\libs\highlevel\abslayer\cmsisos2\lib\cmsisos2.lib + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + + + + + embot + + + embot_core.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + + + embot_app_theBootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + + + embot_app_theCANboardInfo.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + + + embot_os.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + + + embot_os_Task.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + + + embot_os_theCallbackManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + + + embot_app_theJumper.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + + + embot_os_theScheduler.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + + + embot_os_theTimerManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + + + embot_os_Timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + + + embot_app_bootloader_theCANparser.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + + + embot_prot_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + + + embot_prot_can_bootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + + + embot_core_binary.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + + + embot_os_Action.cpp + 8 + ..\..\..\..\embot\os\embot_os_Action.cpp + + + embot_app_theLEDmanager.cpp + 8 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + + + embot_os_rtos.cpp + 8 + ..\..\..\..\embot\os\embot_os_rtos.cpp + + + embot_prot_can_analog_polling.cpp + 8 + ..\..\..\..\embot\prot\can\embot_prot_can_analog_polling.cpp + + + + + embot-hw + + + embot_hw.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + + + embot_hw_bsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + + + embot_hw_FlashStorage.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + + + embot_hw_FlashBurner.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + + + embot_hw_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + + + embot_hw_sys.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + + + embot_hw_flash.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + + + embot_hw_led.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + + + embot_hw_gpio.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + + + embot_hw_timer.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + + + embot_hw_bno055.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_bno055.cpp + + + embot_hw_si7051.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_si7051.cpp + + + embot_hw_i2c.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_i2c.cpp + + + embot_hw_pga308.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_pga308.cpp + + + embot_hw_onewire.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_onewire.cpp + + + embot_hw_adc.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_adc.cpp + + + + + embot-hw-lowlevel + + + embot_hw_lowlevel.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + + + 2 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 1 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + + + embot::hw::bsp + + + embot_hw_bsp_strain2c.cpp + 8 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + + + + + ::CMSIS + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test.sct b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test.sct new file mode 100644 index 0000000000..dc9daa2499 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/proj/strain2c-test.sct @@ -0,0 +1,38 @@ +#! armcc -E +; the above must be on teh first line of teh scatter file ... + +; Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia +; Author: Marco Accame +; email: marco.accame@iit.it +; website: www.robotcub.org +; Permission is granted to copy, distribute, and/or modify this program +; under the terms of the GNU General Public License, version 2 or any +; later version published by the Free Software Foundation. +; +; A copy of the license can be found at +; http://www.robotcub.org/icub/license/gpl.txt +; +; This program is distributed in the hope that it will be useful, but +; WITHOUT ANY WARRANTY; without even the implied warranty of +; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General +; Public License for more details +; due to a bug in linker (in some older versions), you may need to put the whole path ... thus change it by hand +;#include "D:\#inhere\sdl\embedded\arm\embody\body\embenv\envcom\eEmemorymap.h" +;#include "..\..\cfg\eEmemorymap.h" + + +; flash starts from xx and its size is xxx +LR_IROM1 0x08000000 0x0001F000 { ; load region size_region + ER_IROM1 0x08000000 0x0001F000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + RW_IRAM1 0x20000020 0xBFE0 { ; RW data + .ANY (+RW +ZI) + } +} + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/src/embot_code_bootloader-for-test.cpp b/emBODY/eBcode/arch-arm/board/strain2c/test/src/embot_code_bootloader-for-test.cpp new file mode 100644 index 0000000000..7ef06ca511 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/src/embot_code_bootloader-for-test.cpp @@ -0,0 +1,573 @@ + +/* + * Copyright (C) 2022 iCub Tech - Istituto Italiano di Tecnologia + * Author: Davide Tomé + * email: davide.tome@iit.it +*/ + + +// -------------------------------------------------------------------------------------------------------------------- +// - public interface +// -------------------------------------------------------------------------------------------------------------------- + +#include "embot_app_skeleton_os_bootloader.h" + + + +// -------------------------------------------------------------------------------------------------------------------- +// - external dependencies +// -------------------------------------------------------------------------------------------------------------------- + + +#include "embot_core.h" +#include "embot_os_Thread.h" +#include "embot_app_theBootloader.h" +#include "embot_app_bootloader_theCANparser.h" +#include "embot_app_theLEDmanager.h" + +#include "embot_hw_can.h" +#include "embot_hw_si7051.h" +#include "embot_hw_bno055.h" +#include "embot_hw_gpio.h" +#include "embot_hw_pga308.h" +#include "embot_hw_pga308_bsp.h" +#include "embot_hw_onewire_bsp.h" +#include "embot_hw_adc.h" +#include "embot_hw_adc_bsp.h" +#include "embot_prot_can.h" + +#include "embot_core.h" +#include "embot_core_utils.h" +#include "embot_core_binary.h" +#include "embot_prot_can_analog_polling.h" + + +// -------------------------------------------------------------------------------------------------------------------- +// - all the rest +// -------------------------------------------------------------------------------------------------------------------- + +namespace embot { namespace app { namespace skeleton { namespace os { namespace bootloader { + + struct ActivityParam + { + static const embot::core::relTime BlinkFastPeriod = 200*embot::core::time1millisec; + static const embot::core::relTime BlinkSlowPeriod = 500*embot::core::time1millisec; + static const embot::core::relTime BlinkMadlyPeriod = 50*embot::core::time1millisec; + + embot::core::relTime blinkingperiod {BlinkFastPeriod}; + const embot::app::theCANboardInfo::bootloaderInfo *info {nullptr}; + + ActivityParam() = default; + ActivityParam(embot::core::relTime ti, const embot::app::theCANboardInfo::bootloaderInfo *in) : blinkingperiod(ti), info(in) {} + }; + + +}}}}} + + +namespace embot { namespace app { namespace skeleton { namespace os { namespace bootloader { + + constexpr embot::core::relTime timebeforeJump = 5 * embot::core::time1second; + void activity_function(void* param); + ActivityParam activity_param { ActivityParam::BlinkFastPeriod, nullptr}; + + + [[noreturn]] void run(const embot::app::theCANboardInfo::bootloaderInfo &info) + { + + embot::app::theBootloader & bootloader = embot::app::theBootloader::getInstance(); + +// embot::app::theBootloader::evalRes res = bootloader.eval(); +// +// // if in here, it means that we must execute. let's fill the embot::app::theBootloader::Config according to res +// activity_param.info = &info; // i copy into param the info about teh board + embot::app::theBootloader::Config config { {activity_function, &activity_param}, timebeforeJump }; +// +// switch(res) +// { +// case embot::app::theBootloader::evalRes::jumpaftercountdown: +// { +// config.countdown = timebeforeJump; +// activity_param.blinkingperiod = ActivityParam::BlinkFastPeriod; +// } break; + +// case embot::app::theBootloader::evalRes::stayforever: +// { +// config.countdown = 0; +// activity_param.blinkingperiod = ActivityParam::BlinkSlowPeriod; +// } break; +// +// case embot::app::theBootloader::evalRes::jumpfailed: +// case embot::app::theBootloader::evalRes::unexected: +// default: +// { +// config.countdown = 0; +// activity_param.blinkingperiod = ActivityParam::BlinkMadlyPeriod; +// } break; +// } + config.countdown = 0; + // and now we execute. this function is [[noreturn]] + // it inits the hw::bsp and then starts the scheduler. + // the OS init thread will: start timer manager and callback manager, and finally call activity_function(&activity_param). + // + bootloader.execute(config); + + for(;;); + } + + +}}}}} + + + + +namespace embot { namespace app { namespace skeleton { namespace os { namespace bootloader { + + const uint8_t Firmware_vers = 3; + const uint8_t Revision_vers = 0; + const uint8_t Build_number = 0; + + constexpr std::uint8_t maxINPcanframes = 16; + constexpr std::uint8_t maxOUTcanframes = 32; + constexpr embot::os::Event evRXcanframe = 0x00000001; + + static void eventhread_init(embot::os::Thread *t, void *p); + static void eventhread_onevent(embot::os::Thread *t, embot::os::Event evt, void *p); + + static void alerteventhread(void *arg); + + static std::vector outframes; + + + void activity_function(void* param) + { + ActivityParam* pp = reinterpret_cast(param); + + // manage the basic canboardinfo + embot::app::theCANboardInfo &canbrdinfo = embot::app::theCANboardInfo::getInstance(); + canbrdinfo.synch(*activity_param.info); + + // manage the led blinking period + embot::core::relTime period = 0; + if(nullptr != pp) + { + period = pp->blinkingperiod; + } + + // start the led pulser + static const std::initializer_list allleds = {embot::hw::LED::one, embot::hw::LED::two}; + embot::app::theLEDmanager &theleds = embot::app::theLEDmanager::getInstance(); + theleds.init(allleds); + theleds.get(embot::hw::LED::one).on(); + theleds.get(embot::hw::LED::two).on(); + + + // start thread waiting for can messages. + const embot::core::relTime waitEventTimeout = 50*1000; //50*1000; //5*1000*1000; + embot::os::EventThread::Config configEV; + configEV.startup = eventhread_init; + configEV.onevent = eventhread_onevent; + configEV.param = nullptr; + configEV.stacksize = 4*1024; + configEV.priority = embot::os::Priority::high40; + configEV.timeout = waitEventTimeout; + + embot::os::EventThread* eventhread = new embot::os::EventThread; + eventhread->start(configEV); + + // start the canparser + embot::app::bootloader::theCANparser &canparser = embot::app::bootloader::theCANparser::getInstance(); + embot::app::bootloader::theCANparser::Config config {embot::prot::can::Process::bootloader}; + canparser.initialise(config); + + // finally init can. it will be enabled only inside teh startup() of the eventhread + embot::hw::result_t r = embot::hw::resNOK; + embot::hw::can::Config canconfig; + canconfig.rxcapacity = maxINPcanframes; + canconfig.txcapacity = maxOUTcanframes; + canconfig.onrxframe = embot::core::Callback(alerteventhread, eventhread); + embot::hw::can::init(embot::hw::CAN::one, canconfig); + //embot::hw::can::setfilters(embot::hw::CAN::one, embot::app::theCANboardInfo::getInstance().getCANaddress()); // removed for test purpose (no filters) + } + + static void alerteventhread(void *arg) + { + embot::os::EventThread* evtsk = reinterpret_cast(arg); + if(nullptr != evtsk) + { + evtsk->setEvent(evRXcanframe); + } + } + + static void eventhread_init(embot::os::Thread *t, void *p) + { + embot::hw::result_t r = embot::hw::can::enable(embot::hw::CAN::one); + r = r; + outframes.reserve(maxOUTcanframes); + } + + + void getFirmwareVersion() + { + embot::hw::can::Frame canframe; + + canframe.id = 0x551; ; + canframe.size = 8; + canframe.data[0] = Firmware_vers; + canframe.data[1] = Revision_vers; + canframe.data[2] = Build_number; + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + + } + + void testLeds(uint8_t on){ + static const std::initializer_list allleds = {embot::hw::LED::one, embot::hw::LED::two}; + embot::app::theLEDmanager &theleds = embot::app::theLEDmanager::getInstance(); + theleds.init(allleds); + + switch(on){ + case 0: + theleds.get(embot::hw::LED::one).off(); + break; + case 1: + theleds.get(embot::hw::LED::one).on(); + break; + default: break; + } + + } + + + constexpr embot::hw::SI7051 thermometer1 = embot::hw::SI7051::one; + constexpr embot::hw::SI7051 thermometer2 = embot::hw::SI7051::two; + + constexpr embot::hw::si7051::Config thermometerconfig = {}; + embot::hw::si7051::Temperature temp1 {0}; + embot::hw::si7051::Temperature temp2 {0}; + + + void testTemperature(uint8_t tempIN){ + + embot::hw::can::Frame canframe; + static bool init = false; + + // leggo sensore temperatura 1 + if(!init) { + embot::hw::si7051::init(thermometer1, thermometerconfig); + init = true; + } + + embot::hw::si7051::acquisition(embot::hw::SI7051::one, {}); + for(;;) + { + if(true == embot::hw::si7051::operationdone(embot::hw::SI7051::one)) + { + break; + } + } + embot::hw::si7051::read(thermometer1, temp1); + + temp1 = temp1/10; + + // leggo sensore temperatura 2 + init = false; + if(!init) { + embot::hw::si7051::init(thermometer2, thermometerconfig); + init = true; + } + + embot::hw::si7051::acquisition(embot::hw::SI7051::two, {}); + for(;;) + { + if(true == embot::hw::si7051::operationdone(embot::hw::SI7051::two)) + { + break; + } + } + embot::hw::si7051::read(thermometer2, temp2); + + temp2 = temp2/10; + + canframe.id = 0x551; ; + canframe.size = 8; + canframe.data[1] = tempIN; + canframe.data[2] = temp1; + canframe.data[3] = temp2; + + if(((temp1 < tempIN - ((tempIN*30)/100) || temp1 > tempIN +((tempIN*30)/100)) || (temp2 < tempIN - ((tempIN*30)/100) || temp2 > tempIN +((tempIN*30)/100)))) canframe.data[0] = 0xBB; // fail + else canframe.data[0] = 0xAA; // pass + + embot::core::wait(500* embot::core::time1millisec); + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + + } + + + constexpr embot::hw::BNO055 imu = embot::hw::BNO055::one; + constexpr embot::hw::bno055::Config imuconfig = {}; + embot::hw::bno055::Info info; + char chip_id; + + static void testBNO055(){ + embot::hw::can::Frame canframe; + static bool init = false; + + if(!init) { + embot::hw::bno055::init(imu, imuconfig); + init = true; + } + embot::hw::bno055::get(imu, info, 1000); + + for(;;) + { + if(true == embot::hw::bno055::operationdone(embot::hw::BNO055::one)) + { + break; + } + } + + embot::hw::bno055::get(imu, info, 1000); + + canframe.id = 0x551; ; + canframe.size = 8; + canframe.data[0] = info.chipID; + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + + } + + embot::hw::pga308::Config pga308cfg; + std::uint16_t dmabuffer[6]; + std::uint16_t adcvalue[6]; + + volatile bool ready = false; + + void alertdataisready(void *){ + ready = true; + } + + static void testPga308(){ + embot::hw::can::Frame canframe; + static bool init = false; + + // common settings + pga308cfg.powerongpio = embot::hw::pga308::getBSP().getPROP(embot::hw::PGA308::one)->poweron; // embot::hw::GPIO(EN_2V8_GPIO_Port, EN_2V8_Pin); + pga308cfg.poweronstate = embot::hw::gpio::State::SET; + pga308cfg.onewireconfig.rate = embot::hw::onewire::Rate::tenKbps; + pga308cfg.onewireconfig.usepreamble = true; + pga308cfg.onewireconfig.preamble = 0x55; + + // embot::hw::PGA308::one + pga308cfg.onewirechannel = embot::hw::ONEWIRE::one; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::one)->gpio; // embot::hw::GPIO(W_STRAIN1_GPIO_Port, W_STRAIN1_Pin); + embot::hw::pga308::init(embot::hw::PGA308::one, pga308cfg); + + // embot::hw::PGA308::two + pga308cfg.onewirechannel = embot::hw::ONEWIRE::two; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::two)->gpio; //embot::hw::GPIO(W_STRAIN2_GPIO_Port, W_STRAIN2_Pin); + embot::hw::pga308::init(embot::hw::PGA308::two, pga308cfg); + + // embot::hw::PGA308::three + pga308cfg.onewirechannel = embot::hw::ONEWIRE::three; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::three)->gpio;; // embot::hw::GPIO(W_STRAIN3_GPIO_Port, W_STRAIN3_Pin); + embot::hw::pga308::init(embot::hw::PGA308::three, pga308cfg); + + // embot::hw::PGA308::four + pga308cfg.onewirechannel = embot::hw::ONEWIRE::four; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::four)->gpio; // embot::hw::GPIO(W_STRAIN4_GPIO_Port, W_STRAIN4_Pin); + embot::hw::pga308::init(embot::hw::PGA308::four, pga308cfg); + + // embot::hw::PGA308::five + pga308cfg.onewirechannel = embot::hw::ONEWIRE::five; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::five)->gpio; // embot::hw::GPIO(W_STRAIN5_GPIO_Port, W_STRAIN5_Pin); + embot::hw::pga308::init(embot::hw::PGA308::five, pga308cfg); + + // embot::hw::PGA308::six + pga308cfg.onewirechannel = embot::hw::ONEWIRE::six; + pga308cfg.onewireconfig.gpio = embot::hw::onewire::getBSP().getPROP(embot::hw::ONEWIRE::six)->gpio; // embot::hw::GPIO(W_STRAIN6_GPIO_Port, W_STRAIN6_Pin); + embot::hw::pga308::init(embot::hw::PGA308::six, pga308cfg); + + // imporre al pga valori dei registri che abbiano un certo guadagno ed offset + embot::prot::can::analog::polling::PGA308cfg1 cfg1 {}; + embot::prot::can::analog::polling::PGA308cfg1 cfg2 {}; + embot::prot::can::analog::polling::PGA308cfg1 cfg3 {}; + + //configdata.amplifiers_get(setindex, i, cfg1); + // alpha = 96, beta = 4k, where vout = alpha * vin + beta + // valori presi dal documento protocollo a pagina 108 + cfg1.GD = 0x4000; + cfg1.GI = 0x5; + cfg1.S = 0x0; + cfg1.GO = 0x6; + cfg1.Voffsetcoarse = 0x10; + cfg1.Vzerodac = 0x810f; + + //configdata.amplifiers_get(setindex, i, cfg2); + // alpha = 16, beta = 4k, where vout = alpha * vin + beta + // valori presi dal documento protocollo a pagina 108 + cfg2.GD = 0x0000; + cfg2.GI = 0x4; + cfg2.S = 0x0; + cfg2.GO = 0x2; + cfg2.Voffsetcoarse = 0x5e; + cfg2.Vzerodac = 0x8072; + + //configdata.amplifiers_get(setindex, i, cfg3); + // alpha = 8, beta = 4k, where vout = alpha * vin + beta + // valori presi dal documento protocollo a pagina 108 + cfg3.GD = 0x8000; + cfg3.GI = 0x0; + cfg3.S = 0x0; + cfg3.GO = 0x2; + cfg3.Voffsetcoarse = 0x64; + cfg3.Vzerodac = 0x6229; + + embot::hw::pga308::TransferFunctionConfig tfc; + tfc.load(cfg2.GD, cfg2.GI, cfg2.S, cfg2.GO, cfg2.Voffsetcoarse, cfg2.Vzerodac); + // verifica che apha e bet siano 96 e 4k + float alpha = tfc.alpha(); + float beta = tfc.beta(); + // si impone che il pga abbia veramente i valori voluti + + embot::hw::pga308::set(embot::hw::PGA308::one, tfc); + embot::hw::pga308::set(embot::hw::PGA308::two, tfc); + embot::hw::pga308::set(embot::hw::PGA308::three, tfc); + embot::hw::pga308::set(embot::hw::PGA308::four, tfc); + embot::hw::pga308::set(embot::hw::PGA308::five, tfc); + embot::hw::pga308::set(embot::hw::PGA308::six, tfc); + + + + //inizializzo ADC + embot::hw::adc::Config adcConf; + adcConf.numberofitems = 6; + adcConf.destination = dmabuffer; + adcConf.mode = embot::hw::adc::Mode::dma; + adcConf.oncompletion = { alertdataisready, nullptr }; + embot::hw::adc::init(embot::hw::ADC::one, adcConf); + ready = false; + volatile int i{0}; + std::memset(dmabuffer, 0x1, sizeof(dmabuffer)); + embot::hw::adc::start(embot::hw::ADC::one); + embot::core::wait(500* embot::core::time1millisec); + +// while(!ready || i < 1000) { +// embot::core::wait(10* embot::core::time1millisec); +// i = 1 + 10; +// } + embot::hw::adc::stop(embot::hw::ADC::one); + i++; + + canframe.id = 0x551; + canframe.size = 8; + canframe.data[0] = 0xAA; + canframe.data[1] = 0xAA; + canframe.data[2] = 0xAA; + canframe.data[3] = 0xAA; + canframe.data[4] = 0xAA; + canframe.data[5] = 0xAA; + canframe.data[6] = 0xAA; + + for(int k = 0; k < 6; k++){ + if(dmabuffer[k] < 3800 || dmabuffer[k] > 4200) { canframe.data[0] = 0xBB; canframe.data[k+1] = 0xBB;} + } + + + embot::core::wait(500* embot::core::time1millisec); + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + } + + + static void testCAN(){ + + embot::hw::can::Frame canframe; + + canframe.id = 0x551; ; + canframe.size = 8; + canframe.data[0] = 0xAA; + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + + } + + + + + static void testStrain(){ + + embot::hw::can::Frame canframe; + + + + canframe.id = 0x551; + canframe.size = 8; + canframe.data[0] = 0xAA; + + embot::hw::can::put(embot::hw::CAN::one, {canframe.id, canframe.size, canframe.data}); + embot::hw::can::transmit(embot::hw::CAN::one); + + } + static void eventhread_onevent(embot::os::Thread *t, embot::os::EventMask eventmask, void *p) + { + if(0 == eventmask) + { // timeout ... + return; + } + + // we clear the frames to be trasmitted + outframes.clear(); + std::uint8_t remaining = 0; + if(true == embot::core::binary::mask::check(eventmask, evRXcanframe)) + { + embot::hw::can::Frame canframe; + + embot::hw::can::get(embot::hw::CAN::one, canframe, remaining); + + switch(canframe.data[0]){ + + //Check revisione fw collaudo + case 0x00 : embot::core::wait(300* embot::core::time1millisec); getFirmwareVersion(); break; + + //Test led spento + case 0x01 : embot::core::wait(300* embot::core::time1millisec); testLeds(0); break; + + //Test led blu acceso + case 0x02 : embot::core::wait(300* embot::core::time1millisec); testLeds(1); break; + + //Test sensori temperatura + case 0x03 : embot::core::wait(300* embot::core::time1millisec); testTemperature(canframe.data[1]); break; + + //Test BNO055 + case 0x04 : embot::core::wait(300* embot::core::time1millisec); testBNO055(); break; + + //Test pga308 + case 0x05 : embot::core::wait(300* embot::core::time1millisec); testPga308(); break; + + //Test CAN + case 0x06 : embot::core::wait(300* embot::core::time1millisec); testCAN(); break; + + default : break; + } + + } + + + + } + + + + +}}}}} + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/src/main-bootloader.cpp b/emBODY/eBcode/arch-arm/board/strain2c/test/src/main-bootloader.cpp new file mode 100644 index 0000000000..01d1167bc9 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/src/main-bootloader.cpp @@ -0,0 +1,36 @@ + +/* + * Copyright (C) 2019 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + + +#include "embot_app_skeleton_os_bootloader.h" + +// -------------------------------------------------------------------------------------------------------------------- +// bootloader info + +constexpr std::uint8_t defADDRESS = 13; +constexpr embot::app::theCANboardInfo::bootloaderInfo btlInfo +{ + embot::prot::can::Board::strain2, + embot::prot::can::versionOfBOOTLOADER {2, 6}, + defADDRESS, + "I am a strain2" +}; + +// -------------------------------------------------------------------------------------------------------------------- + +int main(void) +{ + embot::app::skeleton::os::bootloader::run(btlInfo); + for(;;); +} + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/test/strain2-canreal-tests.cspsl b/emBODY/eBcode/arch-arm/board/strain2c/test/strain2-canreal-tests.cspsl new file mode 100644 index 0000000000..c53e3d8aa2 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/test/strain2-canreal-tests.cspsl @@ -0,0 +1,10 @@ +[--] ---------------------------------------------- +[--] CANreal Send List +[--] ---------------------------------------------- + 0 0 0 00000000 0 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 1 0 Get FW version 1 00000001 1 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 2 0 Leds OFF 1 00000001 1 01 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 3 0 Leds ON 1 00000001 1 02 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 4 0 Test Temperatura 1 00000001 2 03 25 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 5 0 BNO055 1 00000001 1 04 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 + 6 0 PGA308 1 00000001 1 05 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/bin/.placeholder.txt b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/bin/.placeholder.txt new file mode 100644 index 0000000000..b0eb8200ba --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/bin/.placeholder.txt @@ -0,0 +1 @@ +.placeholder diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal.startup.strain2.v190.s b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal.startup.strain2.v190.s new file mode 100644 index 0000000000..e9551a1aaf --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal.startup.strain2.v190.s @@ -0,0 +1,415 @@ +;********************** COPYRIGHT(c) 2017 STMicroelectronics ****************** +;* File Name : startup_stm32l443xx.s +;* Author : MCD Application Team +;* Version : V1.3.2 +;* Date : 16-June-2017 +;* Description : STM32L443xx Ultra Low Power devices vector table for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the Cortex-M4 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +;* +;* Redistribution and use in source and binary forms, with or without modification, +;* are permitted provided that the following conditions are met: +;* 1. Redistributions of source code must retain the above copyright notice, +;* this list of conditions and the following disclaimer. +;* 2. Redistributions in binary form must reproduce the above copyright notice, +;* this list of conditions and the following disclaimer in the documentation +;* and/or other materials provided with the distribution. +;* 3. Neither the name of STMicroelectronics nor the names of its contributors +;* may be used to endorse or promote products derived from this software +;* without specific prior written permission. +;* +;* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +;* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +;* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +;* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +;* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +;* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +;* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +;* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +;* +;******************************************************************************* +; + +; in case of error from assembler, you surely forgot --cpreproc in menu asm-options/misc-controls +; or may also to include it into asm path in menu asm-options/include-paths +;#include "stm32hal_stg.h" + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Stack_Size EQU 0x00003000 +;Stack_Size EQU STM32HAL_STG_STACKSIZE + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; +Heap_Size EQU 0x00008000 +;Heap_Size EQU STM32HAL_STG_HEAPSIZE + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window WatchDog + DCD PVD_PVM_IRQHandler ; PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection + DCD TAMP_STAMP_IRQHandler ; Tamper and TimeStamps through the EXTI line + DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line + DCD FLASH_IRQHandler ; FLASH + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line0 + DCD EXTI1_IRQHandler ; EXTI Line1 + DCD EXTI2_IRQHandler ; EXTI Line2 + DCD EXTI3_IRQHandler ; EXTI Line3 + DCD EXTI4_IRQHandler ; EXTI Line4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; External Line[9:5]s + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; External Line[15:10] + DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SDMMC1_IRQHandler ; SDMMC1 + DCD 0 ; Reserved + DCD SPI3_IRQHandler ; SPI3 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&2 underrun errors + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel 1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel 2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel 3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel 4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel 5 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD COMP_IRQHandler ; COMP Interrupt + DCD LPTIM1_IRQHandler ; LP TIM1 interrupt + DCD LPTIM2_IRQHandler ; LP TIM2 interrupt + DCD USB_IRQHandler ; USB FS + DCD DMA2_Channel6_IRQHandler ; DMA2 Channel 6 + DCD DMA2_Channel7_IRQHandler ; DMA2 Channel 7 + DCD LPUART1_IRQHandler ; LP UART1 interrupt + DCD QUADSPI_IRQHandler ; Quad SPI global interrupt + DCD I2C3_EV_IRQHandler ; I2C3 event + DCD I2C3_ER_IRQHandler ; I2C3 error + DCD SAI1_IRQHandler ; Serial Audio Interface 1 global interrupt + DCD 0 ; Reserved + DCD SWPMI1_IRQHandler ; Serial Wire Interface 1 global interrupt + DCD TSC_IRQHandler ; Touch Sense Controller global interrupt + DCD LCD_IRQHandler ; LCD global interrupt + DCD AES_IRQHandler ; AES global interrupt + DCD RNG_IRQHandler ; RNG global interrupt + DCD FPU_IRQHandler ; FPU + DCD CRS_IRQHandler ; CRS interrupt + +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_PVM_IRQHandler [WEAK] + EXPORT TAMP_STAMP_IRQHandler [WEAK] + EXPORT RTC_WKUP_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTC_Alarm_IRQHandler [WEAK] + EXPORT SDMMC1_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT COMP_IRQHandler [WEAK] + EXPORT LPTIM1_IRQHandler [WEAK] + EXPORT LPTIM2_IRQHandler [WEAK] + EXPORT USB_IRQHandler [WEAK] + EXPORT DMA2_Channel6_IRQHandler [WEAK] + EXPORT DMA2_Channel7_IRQHandler [WEAK] + EXPORT LPUART1_IRQHandler [WEAK] + EXPORT QUADSPI_IRQHandler [WEAK] + EXPORT I2C3_EV_IRQHandler [WEAK] + EXPORT I2C3_ER_IRQHandler [WEAK] + EXPORT SAI1_IRQHandler [WEAK] + EXPORT SWPMI1_IRQHandler [WEAK] + EXPORT TSC_IRQHandler [WEAK] + EXPORT LCD_IRQHandler [WEAK] + EXPORT AES_IRQHandler [WEAK] + EXPORT RNG_IRQHandler [WEAK] + EXPORT FPU_IRQHandler [WEAK] + EXPORT CRS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_PVM_IRQHandler +TAMP_STAMP_IRQHandler +RTC_WKUP_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTC_Alarm_IRQHandler +SDMMC1_IRQHandler +SPI3_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +COMP_IRQHandler +LPTIM1_IRQHandler +LPTIM2_IRQHandler +USB_IRQHandler +DMA2_Channel6_IRQHandler +DMA2_Channel7_IRQHandler +LPUART1_IRQHandler +QUADSPI_IRQHandler +I2C3_EV_IRQHandler +I2C3_ER_IRQHandler +SAI1_IRQHandler +SWPMI1_IRQHandler +TSC_IRQHandler +LCD_IRQHandler +AES_IRQHandler +RNG_IRQHandler +FPU_IRQHandler +CRS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE***** diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal_stg.h b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal_stg.h new file mode 100644 index 0000000000..a3b9b721d4 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/cfg/stm32hal_stg.h @@ -0,0 +1,54 @@ + + + +// - include guard ---------------------------------------------------------------------------------------------------- +#ifndef __STM32HAL_STG_H_ +#define __STM32HAL_STG_H_ + +#ifdef __cplusplus +extern "C" { +#endif + + + +// -------------------------------------------------------------------------------------------------------------------- +//-------- <<< Use Configuration Wizard in Context Menu >>> ----------------------------------------------------------- +// -------------------------------------------------------------------------------------------------------------------- + + +// STACK & HEAP +// It contains stack and heap size and some externally functions + +// stack size <0x0-0xFFFFFFFF:8> +// define how much stack you want. +#ifndef STM32HAL_STG_STACKSIZE + #define STM32HAL_STG_STACKSIZE 0x00002000 +#endif + +// heap size <0x0-0xFFFFFFFF:8> +// define how much heap you want. +#ifndef STM32HAL_STG_HEAPSIZE + #define STM32HAL_STG_HEAPSIZE 0x00008000 +#endif + +// SYS module + + + + +// -------------------------------------------------------------------------------------------------------------------- +//------------- <<< end of configuration section >>> ------------------------------------------------------------------ +// -------------------------------------------------------------------------------------------------------------------- + + + +#ifdef __cplusplus +} // closing brace for extern "C" +#endif + +#endif // include-guard + + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-application-v6.sct b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-application-v6.sct new file mode 100644 index 0000000000..b38f3aa3d5 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-application-v6.sct @@ -0,0 +1,41 @@ +;#! armcc -E +; the above must be on teh first line of teh scatter file ... + +; Copyright (C) 2011 Department of Robotics Brain and Cognitive Sciences - Istituto Italiano di Tecnologia +; Author: Marco Accame +; email: marco.accame@iit.it +; website: www.robotcub.org +; Permission is granted to copy, distribute, and/or modify this program +; under the terms of the GNU General Public License, version 2 or any +; later version published by the Free Software Foundation. +; +; A copy of the license can be found at +; http://www.robotcub.org/icub/license/gpl.txt +; +; This program is distributed in the hope that it will be useful, but +; WITHOUT ANY WARRANTY; without even the implied warranty of +; MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General +; Public License for more details +; due to a bug in linker (in some older versions), you may need to put the whole path ... thus change it by hand +;#include "D:\#inhere\sdl\embedded\arm\embody\body\embenv\envcom\eEmemorymap.h" +;#include "..\..\cfg\eEmemorymap.h" + + +; flash starts from xx and its size is xxx +; 128k is: LR_IROM1 0x08020000 0x00020000 { ; load region size_region +; if we want to start at 80k, with size 256-80-4 and have a hole of 4k on top ... LR_IROM1 0x08014000 0x0002B000 { ; load region size_region +;LR_IROM1 0x08014000 0x0002B000 { ; load region size_region +LR_IROM1 0x08014000 0x0002B000 { ; load region size_region + ER_IROM1 0x08014000 0x0002B000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + RW_IRAM1 0x20000020 0xBFE0 { ; RW data + .ANY (+RW +ZI) + } +} + + + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvoptx b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvoptx new file mode 100644 index 0000000000..9ce641ac94 --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvoptx @@ -0,0 +1,981 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj; *.o + *.lib + *.txt; *.h; *.inc; *.md + *.plm + *.cpp + 0 + + + + 0 + 0 + + + + strain2-updtbtl-ulpro-v190 + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 0 + + + + + + + + + + + BIN\UL2CM3.DLL + + + + 0 + UL2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ULP2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + + + + + + + 0 + 1 + frame + + + + + 1 + 0 + hcan->pTxMsg->Data + 0 + + + + + 2 + 0 + 0x08040000 + 0 + + + + 0 + + + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 0 + 0 + 2 + 33000000 + + + + + + strain2-updtbtl-0offset + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 0 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 0 + + + + + + + + + + + BIN\UL2CM3.DLL + + + + 0 + UL2CM3 + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L443RCTx$CMSIS\Flash\STM32L4xx_256.FLM)) + + + 0 + ULP2CM3 + -UP1123158 -O206 -S0 -C0 -P00 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO18 -TC16000000 -TP18 -TDX0 -TDD0 -TDS8007 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO7 -FD20000000 -FC1000 -FN1 -FF0STM32L4xx_256.FLM -FS08000000 -FL040000 -FP0($$Device:STM32L433RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + 0 + ARMRTXEVENTFLAGS + -L70 -Z18 -C0 -M0 -T1 + + + 0 + DLGTARM + (1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0) + + + 0 + ARMDBGFLAGS + + + + 0 + DLGUARM + + + + + + 0 + 0 + 111 + 1 +
134246820
+ 0 + 0 + 0 + 0 + 0 + 1 + ../src/main-updaterofbootloader.cpp + + \\mtb4_bootloader\../src/main-updaterofbootloader.cpp\111 +
+ + 1 + 0 + 580 + 1 +
134251180
+ 0 + 0 + 0 + 0 + 0 + 1 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + + \\mtb4_bootloader\../../../../../../eBcode/arch-arm/embot/app/embot_app_bootloader_theCANparser.cpp\580 +
+ + 2 + 0 + 50 + 1 +
0
+ 0 + 0 + 0 + 0 + 0 + 0 + ../src/main-updaterofbootloader.cpp + + +
+
+ + + 0 + 1 + frame + + + 1 + 1 + config + + + 2 + 1 + pImpl->config + + + + + 1 + 0 + hcan->pTxMsg->Data + 0 + + + + + 2 + 0 + 0x08040000 + 0 + + + + 0 + + + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 1 + 0 + 2 + 10000000 + +
+
+ + + main + 1 + 0 + 0 + 0 + + 1 + 1 + 8 + 0 + 0 + 0 + ../src/main-updaterofbootloader.cpp + main-updaterofbootloader.cpp + 0 + 0 + + + 1 + 2 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_updaterofbootloader.cpp + embot_app_skeleton_os_updaterofbootloader.cpp + 0 + 0 + + + + + stm32hal-nucleo + 1 + 0 + 0 + 0 + + 2 + 3 + 4 + 0 + 0 + 0 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + stm32hal.strain2c.v1B0.lib + 0 + 0 + + + + + stm32hal-config + 1 + 0 + 0 + 0 + + 3 + 4 + 2 + 0 + 0 + 0 + ..\cfg\stm32hal.startup.strain2.v190.s + stm32hal.startup.strain2.v190.s + 0 + 0 + + + + + osal + 0 + 0 + 0 + 0 + + 4 + 5 + 1 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\src\eventviewer.c + eventviewer.c + 0 + 0 + + + 4 + 6 + 4 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + osal.cm4.dbg.lib + 0 + 0 + + + 4 + 7 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_rtos.cpp + embot_os_rtos.cpp + 0 + 0 + + + + + embot + 0 + 0 + 0 + 0 + + 5 + 8 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\os\embot_os_Action.cpp + embot_os_Action.cpp + 0 + 0 + + + 5 + 9 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + embot_core_binary.cpp + 0 + 0 + + + 5 + 10 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + embot_app_theBootloader.cpp + 0 + 0 + + + 5 + 11 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + embot_app_theCANboardInfo.cpp + 0 + 0 + + + 5 + 12 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + embot_os.cpp + 0 + 0 + + + 5 + 13 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + embot_os_Thread.cpp + 0 + 0 + + + 5 + 14 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + embot_os_theCallbackManager.cpp + 0 + 0 + + + 5 + 15 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + embot_app_theJumper.cpp + 0 + 0 + + + 5 + 16 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + embot_os_theScheduler.cpp + 0 + 0 + + + 5 + 17 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + embot_os_theTimerManager.cpp + 0 + 0 + + + 5 + 18 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + embot_os_Timer.cpp + 0 + 0 + + + 5 + 19 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + embot_app_bootloader_theCANparser.cpp + 0 + 0 + + + 5 + 20 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + embot_prot_can.cpp + 0 + 0 + + + 5 + 21 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + embot_prot_can_bootloader.cpp + 0 + 0 + + + 5 + 22 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + embot_app_theLEDmanager.cpp + 0 + 0 + + + 5 + 23 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + embot_core.cpp + 0 + 0 + + + + + embot-hw + 0 + 0 + 0 + 0 + + 6 + 24 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + embot_hw_FlashBurner.cpp + 0 + 0 + + + 6 + 25 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + embot_hw_FlashStorage.cpp + 0 + 0 + + + 6 + 26 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + embot_hw_can.cpp + 0 + 0 + + + 6 + 27 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + embot_hw_sys.cpp + 0 + 0 + + + 6 + 28 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + embot_hw_flash.cpp + 0 + 0 + + + 6 + 29 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + embot_hw_led.cpp + 0 + 0 + + + 6 + 30 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + embot_hw_bsp.cpp + 0 + 0 + + + 6 + 31 + 8 + 0 + 0 + 0 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + embot_hw.cpp + 0 + 0 + + + 6 + 32 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + embot_hw_timer.cpp + 0 + 0 + + + 6 + 33 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + embot_hw_gpio.cpp + 0 + 0 + + + + + embot-hw-lowlevel + 0 + 0 + 0 + 0 + + 7 + 34 + 8 + 0 + 0 + 0 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + embot_hw_lowlevel.cpp + 0 + 0 + + + + + embot::hw::bsp + 1 + 0 + 0 + 0 + + 8 + 35 + 8 + 0 + 0 + 0 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + embot_hw_bsp_strain2c.cpp + 0 + 0 + + + + + ::CMSIS + 0 + 0 + 0 + 1 + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvprojx b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvprojx new file mode 100644 index 0000000000..47f120087c --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/proj/strain2c-updaterofbootloader-v6.uvprojx @@ -0,0 +1,1465 @@ + + + + 2.1 + +
### uVision Project, (C) Keil Software
+ + + + strain2-updtbtl-ulpro-v190 + 0x4 + ARM-ADS + 6180000::V6.18::ARMCLANG + 1 + + + STM32L452RCIx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x00020000) IRAM2(0x10000000,0x00008000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L452RCIx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L452RCIx$CMSIS\SVD\STM32L4x2.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + strain2c_ub_v1B0 + 1 + 0 + 1 + 1 + 1 + .\lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\Obj\strain2c_ub_v1B0.hex ..\bin\strain2c.updaterofbootloader.v1B0.hex + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 0 + 0x10000000 + 0x8000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 8 + 1 + 1 + 0 + 0 + 0 + + -Wno-pragma-pack -Wno-deprecated-register + USE_STM32HAL STM32HAL_BOARD_STRAIN2C STM32HAL_DRIVER_V1B0 not_STRAIN2_APP_AT_128K + + ..\src-plus;..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\api;..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\api;..\..\..\..\..\..\eBcode\arch-arm\libs\lowlevel\stm32hal\api;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\..\..\eBcode\arch-arm\embot\app;..\..\..\..\..\..\eBcode\arch-arm\embot\i2h;..\..\..\..\..\..\eBcode\arch-arm\embot\hw;..\..\..\..\..\..\eBcode\arch-arm\embot\os;..\..\..\..\..\..\eBcode\arch-arm\embot;..\..\..\..\..\..\eBcode\arch-arm\embot\binary;..\..\..\..\..\..\..\..\icub-firmware-shared\can\canProtocolLib;..\..\..\..\embot\app\skeleton;..\..\..\..\embot\prot\can;..\..\bsp + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + .\strain2c-application-v6.sct + + + --diag_suppress=L6329 + + + + + + + + main + + + main-updaterofbootloader.cpp + 8 + ../src/main-updaterofbootloader.cpp + + + embot_app_skeleton_os_updaterofbootloader.cpp + 8 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_updaterofbootloader.cpp + + + + + stm32hal-nucleo + + + stm32hal.strain2c.v1B0.lib + 4 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + + + + + stm32hal-config + + + stm32hal.startup.strain2.v190.s + 2 + ..\cfg\stm32hal.startup.strain2.v190.s + + + + + osal + + + eventviewer.c + 1 + ..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\src\eventviewer.c + + + osal.cm4.dbg.lib + 4 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + + + embot_os_rtos.cpp + 8 + ..\..\..\..\embot\os\embot_os_rtos.cpp + + + + + embot + + + embot_os_Action.cpp + 8 + ..\..\..\..\embot\os\embot_os_Action.cpp + + + embot_core_binary.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + + + embot_app_theBootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + + + embot_app_theCANboardInfo.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + + + embot_os.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + + + embot_os_Thread.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + + + embot_os_theCallbackManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + + + embot_app_theJumper.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + + + embot_os_theScheduler.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + + + embot_os_theTimerManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + + + embot_os_Timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + + + embot_app_bootloader_theCANparser.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + + + embot_prot_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + + + embot_prot_can_bootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + + + embot_app_theLEDmanager.cpp + 8 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + + + embot_core.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + + + + + embot-hw + + + embot_hw_FlashBurner.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + + + embot_hw_FlashStorage.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + + + embot_hw_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + + + embot_hw_sys.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + + + embot_hw_flash.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + + + embot_hw_led.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + + + embot_hw_bsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + + + embot_hw.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + + + embot_hw_timer.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + + + embot_hw_gpio.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + + + + + embot-hw-lowlevel + + + embot_hw_lowlevel.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + + + 2 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 1 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + + + embot::hw::bsp + + + embot_hw_bsp_strain2c.cpp + 8 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + + + + + ::CMSIS + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + + + strain2-updtbtl-0offset + 0x4 + ARM-ADS + 6120000::V6.12::.\ARMCLANG + 1 + + + STM32L443RCTx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x0000C000) IRAM2(0x10000000,0x00004000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L443RCTx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L443RCTx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L443RCTx$CMSIS\SVD\STM32L4x3.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + strain2_0_ubootloader + 1 + 0 + 1 + 1 + 1 + .\lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\Obj\strain2_0_ubootloader.hex ..\bin\strain2.0.updaterofbootloader.hex + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0xc000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0xc000 + + + 0 + 0x10000000 + 0x4000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 6 + 1 + 1 + 0 + 0 + 0 + + -Wno-pragma-pack -Wno-deprecated-register + USE_STM32HAL STM32HAL_BOARD_STRAIN2 STM32HAL_DRIVER_V190 EMBOT_APPL_ZEROOFFSET + + ..\src-plus;..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\api;..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\api;..\..\..\..\..\..\eBcode\arch-arm\embobj\core\exec\multitask;..\..\..\..\..\..\..\..\icub-firmware-shared\eth\embobj\core\core;..\..\..\..\..\..\eBcode\arch-arm\libs\lowlevel\stm32hal\api;..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core;..\..\..\..\..\..\eBcode\arch-arm\embot\app;..\..\..\..\..\..\eBcode\arch-arm\embot\i2h;..\..\..\..\..\..\eBcode\arch-arm\embot\hw;..\..\..\..\..\..\eBcode\arch-arm\embot\os;..\..\..\..\..\..\eBcode\arch-arm\embot;..\..\..\..\..\..\eBcode\arch-arm\embot\binary;..\..\..\..\..\..\..\..\icub-firmware-shared\can\canProtocolLib + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + .\strain2-application0offset.sct + + + --diag_suppress=L6329 + + + + + + + + main + + + main-updaterofbootloader.cpp + 8 + ../src/main-updaterofbootloader.cpp + + + embot_app_skeleton_os_updaterofbootloader.cpp + 8 + ..\..\..\..\embot\app\skeleton\embot_app_skeleton_os_updaterofbootloader.cpp + + + + + stm32hal-nucleo + + + stm32hal.strain2c.v1B0.lib + 4 + ..\..\..\..\libs\lowlevel\stm32hal\lib\stm32hal.strain2c.v1B0.lib + + + + + stm32hal-config + + + stm32hal.startup.strain2.v190.s + 2 + ..\cfg\stm32hal.startup.strain2.v190.s + + + + + osal + + + eventviewer.c + 1 + ..\..\..\..\..\..\eBcode\arch-arm\libs\midware\eventviewer\src\eventviewer.c + + + osal.cm4.dbg.lib + 4 + ..\..\..\..\..\..\eBcode\arch-arm\libs\highlevel\abslayer\osal\lib\osal.cm4.dbg.lib + + + embot_os_rtos.cpp + 8 + ..\..\..\..\embot\os\embot_os_rtos.cpp + + + + + embot + + + embot_os_Action.cpp + 8 + ..\..\..\..\embot\os\embot_os_Action.cpp + + + embot_core_binary.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core_binary.cpp + + + embot_app_theBootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theBootloader.cpp + + + embot_app_theCANboardInfo.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theCANboardInfo.cpp + + + embot_os.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os.cpp + + + embot_os_Thread.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Thread.cpp + + + embot_os_theCallbackManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theCallbackManager.cpp + + + embot_app_theJumper.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_theJumper.cpp + + + embot_os_theScheduler.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theScheduler.cpp + + + embot_os_theTimerManager.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_theTimerManager.cpp + + + embot_os_Timer.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\os\embot_os_Timer.cpp + + + embot_app_bootloader_theCANparser.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\app\embot_app_bootloader_theCANparser.cpp + + + embot_prot_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can.cpp + + + embot_prot_can_bootloader.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\prot\can\embot_prot_can_bootloader.cpp + + + embot_app_theLEDmanager.cpp + 8 + ..\..\..\..\embot\app\embot_app_theLEDmanager.cpp + + + embot_core.cpp + 8 + ..\..\..\..\..\..\..\..\icub-firmware-shared\embot\core\embot_core.cpp + + + + + embot-hw + + + embot_hw_FlashBurner.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashBurner.cpp + + + embot_hw_FlashStorage.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_FlashStorage.cpp + + + embot_hw_can.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_can.cpp + + + embot_hw_sys.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_sys.cpp + + + embot_hw_flash.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_flash.cpp + + + embot_hw_led.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_led.cpp + + + embot_hw_bsp.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw_bsp.cpp + + + embot_hw.cpp + 8 + ..\..\..\..\..\..\eBcode\arch-arm\embot\hw\embot_hw.cpp + + + embot_hw_timer.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_timer.cpp + + + embot_hw_gpio.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_gpio.cpp + + + + + embot-hw-lowlevel + + + embot_hw_lowlevel.cpp + 8 + ..\..\..\..\embot\hw\embot_hw_lowlevel.cpp + + + 2 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 1 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + + + embot::hw::bsp + + + embot_hw_bsp_strain2c.cpp + 8 + ..\..\bsp\embot_hw_bsp_strain2c.cpp + + + + + ::CMSIS + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + <Project Info> + 0 + 1 + + + + +
diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader-legacy.cpp b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader-legacy.cpp new file mode 100644 index 0000000000..3cd19df01a --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader-legacy.cpp @@ -0,0 +1,179 @@ + + +#include "embot_app_theCANboardInfo.h" +#include "embot.h" +#include "embot_common.h" +#include "embot_binary.h" +#include "stm32hal.h" // to see bsp_led_init etc +//#include "embot_i2h.h" +#include "embot_hw.h" +#include "embot_hw_can.h" +#include "embot_hw_led.h" +#include "embot_hw_FlashStorage.h" +#include "embot_sys_theStorage.h" +#include "embot_app_theBootloader.h" +#include "embot_app_bootloader_theCANparser.h" +#include "embot_app_canprotocol.h" +#include "embot_app_theLEDmanager.h" +#include "embot_hw_flash.h" + + +struct ActivityParam +{ + uint32_t blinkingperiod; +}; + +static void bl_activity(void* param); + +static const embot::core::relTime BlinkSlowPeriod = 500*embot::core::time1millisec; + +static ActivityParam activity_param = { .blinkingperiod = BlinkSlowPeriod }; + + +// use build 222 for all the updaterofbootloader +static const embot::app::canprotocol::versionOfAPPLICATION vAP = {2, 3 , 222}; +static const embot::app::canprotocol::versionOfCANPROTOCOL vCP = {2, 0}; + +static const std::uint32_t address = embot::hw::flash::getpartition(embot::hw::FLASH::application).address; +static const std::uint32_t vectorlocation = address - embot::hw::flash::getpartition(embot::hw::FLASH::whole).address; + +int main(void) +{ + if(0 != vectorlocation) + { + embot::hw::sys::relocatevectortable(vectorlocation); + } + + embot::app::theBootloader & bootloader = embot::app::theBootloader::getInstance(); + + activity_param.blinkingperiod = BlinkSlowPeriod; + embot::app::theBootloader::Config config; + config.userdeflauncher = embot::core::Callback(bl_activity, &activity_param); + config.countdown = 0; + + bootloader.execute(config); + + for(;;); + +} + + + +static void eventbasedtask_onevent(embot::sys::Task *t, embot::core::Event evt, void *p); +static void eventbasedtask_init(embot::sys::Task *t, void *p); + +static const embot::core::Event evRXcanframe = 0x00000001; + +static embot::sys::EventTask* eventbasedtask = nullptr; + +static void alerteventbasedtask(void *arg); + +static std::vector outframes; + +static void bl_activity(void* param) +{ + // manage the led blinking + ActivityParam* pp = (ActivityParam*) param; + uint32_t period = 0; + if(nullptr != pp) + { + period = pp->blinkingperiod; + } + + static const std::initializer_list allleds = {embot::hw::LED::one}; + embot::app::theLEDmanager &theleds = embot::app::theLEDmanager::getInstance(); + theleds.init(allleds); + theleds.get(embot::hw::LED::one).pulse(period, 0); + + // manage the basic canboardinfo fot this special application + embot::app::theCANboardInfo &canbrdinfo = embot::app::theCANboardInfo::getInstance(); + canbrdinfo.synch(vAP, vCP); + + + // start task waiting for can messages. + const embot::core::relTime waitEventTimeout = 50*embot::core::time1millisec; + embot::sys::EventTask::Config configEV; + configEV.startup = eventbasedtask_init; + configEV.onevent = eventbasedtask_onevent; + configEV.param = nullptr; + configEV.stacksize = 4*1024; + configEV.priority = embot::sys::Priority::high200; + configEV.timeout = waitEventTimeout; + + eventbasedtask = new embot::sys::EventTask; + eventbasedtask->start(configEV); + + // start canparser + embot::app::bootloader::theCANparser &canparser = embot::app::bootloader::theCANparser::getInstance(); + embot::app::bootloader::theCANparser::Config config; + config.owner = embot::app::canprotocol::Process::application; + + canparser.initialise(config); + + // finally start can. i keep it as last because i dont want that the isr-handler calls its onrxframe() + // before the eventbasedtask is created. + embot::hw::result_t r = embot::hw::resNOK; + embot::hw::can::Config canconfig; // default is tx/rxcapacity=8 + canconfig.txcapacity = 12; + canconfig.onrxframe = embot::core::Callback(alerteventbasedtask, nullptr); + r = embot::hw::can::init(embot::hw::CAN::one, canconfig); + r = embot::hw::can::setfilters(embot::hw::CAN::one, embot::app::theCANboardInfo::getInstance().getCANaddress()); + r = r; +} + + +static void alerteventbasedtask(void *arg) +{ + if(nullptr != eventbasedtask) + { + eventbasedtask->setEvent(evRXcanframe); + } +} + + +static void eventbasedtask_init(embot::sys::Task *t, void *p) +{ + embot::hw::result_t r = embot::hw::can::enable(embot::hw::CAN::one); + r = r; + + outframes.reserve(12); +} + + + +static void eventbasedtask_onevent(embot::sys::Task *t, embot::core::Event evt, void *p) +{ + + if(true == embot::core::binary::mask::check(evt, evRXcanframe)) + { + embot::hw::can::Frame frame; + std::uint8_t remaining = 0; + if(embot::hw::resOK == embot::hw::can::get(embot::hw::CAN::one, frame, remaining)) + { + outframes.clear(); + embot::app::bootloader::theCANparser &canparser = embot::app::bootloader::theCANparser::getInstance(); + if(true == canparser.process(frame, outframes)) + { + std::uint8_t num = outframes.size(); + for(std::uint8_t i=0; i 0) + { + eventbasedtask->setEvent(evRXcanframe); + } + } + } + +} + + +/// + + diff --git a/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader.cpp b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader.cpp new file mode 100644 index 0000000000..38c224154a --- /dev/null +++ b/emBODY/eBcode/arch-arm/board/strain2c/updaterofbootloader/src/main-updaterofbootloader.cpp @@ -0,0 +1,30 @@ + +/* + * Copyright (C) 2019 iCub Tech - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it +*/ + + +#include "embot_app_skeleton_os_updaterofbootloader.h" + +// -------------------------------------------------------------------------------------------------------------------- +// application info + +constexpr embot::app::theCANboardInfo::applicationInfo appInfo +{ + embot::prot::can::versionOfAPPLICATION {2, 7, 222}, // keep build = 222 so that we recognise it + embot::prot::can::versionOfCANPROTOCOL {2, 0} +}; + +// -------------------------------------------------------------------------------------------------------------------- + +int main(void) +{ + embot::app::skeleton::os::updaterofbootloader::run(appInfo); + for(;;); +} + +// - end-of-file (leave a blank line after)---------------------------------------------------------------------------- + + diff --git a/emBODY/eBcode/arch-arm/embobj/plus/can/EOtheCANmapping.c b/emBODY/eBcode/arch-arm/embobj/plus/can/EOtheCANmapping.c index 334a0a7a9e..9dc6f6f009 100644 --- a/emBODY/eBcode/arch-arm/embobj/plus/can/EOtheCANmapping.c +++ b/emBODY/eBcode/arch-arm/embobj/plus/can/EOtheCANmapping.c @@ -743,18 +743,18 @@ extern eObool_t eocanmap_BRDisCompatible(eObrd_cantype_t brd, eOprotEndpoint_t e // brd: static const uint32_t tableB[] = // [epen] { - (1 << eobrd_cantype_mc4) | (1 << eobrd_cantype_foc) | (1 << eobrd_cantype_pmc) | (1 << eobrd_cantype_amcbldc), // joint - (1 << eobrd_cantype_mc4) | (1 << eobrd_cantype_foc) | (1 << eobrd_cantype_pmc) | (1 << eobrd_cantype_amcbldc), // motor - (1 << eobrd_cantype_strain) | (1 << eobrd_cantype_strain2), // strain - (1 << eobrd_cantype_mais), // mais - (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_mtb4c), // temperature - (1 << eobrd_cantype_mtb), // inertial - (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_rfe) | (1 << eobrd_cantype_mtb4c), // inertial3 + (1 << eobrd_cantype_mc4) | (1 << eobrd_cantype_foc) | (1 << eobrd_cantype_pmc) | (1 << eobrd_cantype_amcbldc), // joint + (1 << eobrd_cantype_mc4) | (1 << eobrd_cantype_foc) | (1 << eobrd_cantype_pmc) | (1 << eobrd_cantype_amcbldc), // motor + (1 << eobrd_cantype_strain) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_strain2c), // strain + (1 << eobrd_cantype_mais), // mais + (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_mtb4c) | (1 << eobrd_cantype_strain2c), // temperature + (1 << eobrd_cantype_mtb), // inertial + (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_rfe) | (1 << eobrd_cantype_mtb4c) | (1 << eobrd_cantype_strain2c), // inertial3 (1 << eobrd_cantype_psc), // psc (1 << eobrd_cantype_mtb4fap) | (1 << eobrd_cantype_pmc) | (1 << eobrd_cantype_psc), // pos - (1 << eobrd_cantype_strain) | (1 << eobrd_cantype_strain2), // ft + (1 << eobrd_cantype_strain) | (1 << eobrd_cantype_strain2) | (1 << eobrd_cantype_strain2c), // ft (1 << eobrd_cantype_bms), // bs - (1 << eobrd_cantype_mtb) | (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_psc) | (1 << eobrd_cantype_mtb4c) // skin // skin + (1 << eobrd_cantype_mtb) | (1 << eobrd_cantype_mtb4) | (1 << eobrd_cantype_psc) | (1 << eobrd_cantype_mtb4c) // skin }; EO_VERIFYsizeof(tableB, sizeof(const uint32_t)*(eocanmap_entities_maxnumberof)) // it is safe to use brd because it is can hence it is < 32 diff --git a/emBODY/eBcode/arch-arm/embot/prot/can/embot_prot_can.h b/emBODY/eBcode/arch-arm/embot/prot/can/embot_prot_can.h index ca719c8a86..e3d87931c1 100644 --- a/emBODY/eBcode/arch-arm/embot/prot/can/embot_prot_can.h +++ b/emBODY/eBcode/arch-arm/embot/prot/can/embot_prot_can.h @@ -53,7 +53,7 @@ namespace embot { namespace prot { namespace can { enum class Board { mtb = 5, strain = 6, mais = 7, mtb4 = 11, strain2 = 12, rfe = 13, sg3 = 14, psc = 15, mtb4w = 16, - pmc = 17, amcbldc = 18, bms = 19, mtb4c = 20, mtb4fap = 21, none = 254, unknown = 0xff }; + pmc = 17, amcbldc = 18, bms = 19, mtb4c = 20, mtb4fap = 21, strain2c = 22, none = 254, unknown = 0xff }; enum class Process { bootloader = 0, application = 1, unknown = 0xff }; diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_board.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_board.h index 8d337cee67..c4e9e3f700 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_board.h +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_board.h @@ -516,6 +516,34 @@ extern void stm32hal_board_init(void); #else #error unsupported driver version for mtb4fap #endif + +#elif defined(STM32HAL_BOARD_STRAIN2C) + + + #if(STM32HAL_DRIVER_VERSION == 0x1B0) + + #if !defined(CPU_AT_80MHZ) + #define CPU_AT_80MHZ + #endif + + #include "../src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h" + + #include "../src/board/strain2c/v1B0/inc/adc.h" + #include "../src/board/strain2c/v1B0/inc/can.h" + #include "../src/board/strain2c/v1B0/inc/dma.h" + #include "../src/board/strain2c/v1B0/inc/gpio.h" + #include "../src/board/strain2c/v1B0/inc/i2c.h" + #include "../src/board/strain2c/v1B0/inc/main.h" + #include "../src/board/strain2c/v1B0/inc/rng.h" + #include "../src/board/strain2c/v1B0/inc/tim.h" + #include "../src/board/strain2c/v1B0/inc/usart.h" + + #include "../src/board/strain2c/v1B0/inc/stm32l4xx_it.h" + + #else + #error unsupported driver version for strain2c + #endif + #else #error STM32HAL: you must define a STM32HAL_BOARD_${B} #endif diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_define.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_define.h index 4cb4aee01b..a63934f8ea 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_define.h +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_define.h @@ -310,7 +310,23 @@ extern "C" { // of family STM32L4 but in STM32HAL_ format #if !defined(STM32HAL_STM32L4) #define STM32HAL_STM32L4 + #endif +#elif defined(STM32HAL_BOARD_STRAIN2C) + + // it has a STM32L452xx mpu + #if !defined(STM32L452xx) + #define STM32L452xx + #endif + + // of family STM32L4 + #if !defined(STM32L4) + #define STM32L4 #endif + + // of family STM32L4 but in STM32HAL_ format + #if !defined(STM32HAL_STM32L4) + #define STM32HAL_STM32L4 + #endif #else #error STM32HAL: you must define a STM32HAL_BOARD_${BRD} #endif diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_driver.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_driver.h index 685810abd4..c9450641ef 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_driver.h +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/api/stm32hal_driver.h @@ -183,7 +183,15 @@ extern "C" { #if !defined(STM32HAL_DRIVER_V1D3) #define STM32HAL_DRIVER_V1D3 #endif - #define STM32HAL_DRIVER_VERSION 0x1D3 + #define STM32HAL_DRIVER_VERSION 0x1D3 + +#elif defined(STM32HAL_BOARD_STRAIN2C) + + // one drive only: v1B0 + #if !defined(STM32HAL_DRIVER_V1B0) + #define STM32HAL_DRIVER_V1B0 + #endif + #define STM32HAL_DRIVER_VERSION 0x1B0 #else #error STM32HAL: the STM32HAL_BOARD_${B} is undefined diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/cubemx/strain2c/strain2c.ioc b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/cubemx/strain2c/strain2c.ioc new file mode 100644 index 0000000000..ea56ecbc5e --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/cubemx/strain2c/strain2c.ioc @@ -0,0 +1,452 @@ +#MicroXplorer Configuration settings - do not modify +ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_1 +ADC1.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_2 +ADC1.Channel-2\#ChannelRegularConversion=ADC_CHANNEL_3 +ADC1.Channel-3\#ChannelRegularConversion=ADC_CHANNEL_4 +ADC1.Channel-4\#ChannelRegularConversion=ADC_CHANNEL_5 +ADC1.Channel-5\#ChannelRegularConversion=ADC_CHANNEL_6 +ADC1.ClockPrescaler=ADC_CLOCK_ASYNC_DIV2 +ADC1.ContinuousConvMode=ENABLE +ADC1.DMAContinuousRequests=ENABLE +ADC1.EOCSelection=ADC_EOC_SEQ_CONV +ADC1.IPParameters=Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,OffsetNumber-0\#ChannelRegularConversion,NbrOfConversionFlag,master,ContinuousConvMode,EOCSelection,OversamplingMode,RightBitShift,Ratio,Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,OffsetNumber-1\#ChannelRegularConversion,Rank-2\#ChannelRegularConversion,Channel-2\#ChannelRegularConversion,SamplingTime-2\#ChannelRegularConversion,OffsetNumber-2\#ChannelRegularConversion,Rank-3\#ChannelRegularConversion,Channel-3\#ChannelRegularConversion,SamplingTime-3\#ChannelRegularConversion,OffsetNumber-3\#ChannelRegularConversion,Rank-4\#ChannelRegularConversion,Channel-4\#ChannelRegularConversion,SamplingTime-4\#ChannelRegularConversion,OffsetNumber-4\#ChannelRegularConversion,Rank-5\#ChannelRegularConversion,Channel-5\#ChannelRegularConversion,SamplingTime-5\#ChannelRegularConversion,OffsetNumber-5\#ChannelRegularConversion,NbrOfConversion,ClockPrescaler,DMAContinuousRequests,Overrun +ADC1.NbrOfConversion=6 +ADC1.NbrOfConversionFlag=1 +ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.OffsetNumber-1\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.OffsetNumber-2\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.OffsetNumber-3\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.OffsetNumber-4\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.OffsetNumber-5\#ChannelRegularConversion=ADC_OFFSET_NONE +ADC1.Overrun=ADC_OVR_DATA_OVERWRITTEN +ADC1.OversamplingMode=ENABLE +ADC1.Rank-0\#ChannelRegularConversion=1 +ADC1.Rank-1\#ChannelRegularConversion=2 +ADC1.Rank-2\#ChannelRegularConversion=3 +ADC1.Rank-3\#ChannelRegularConversion=4 +ADC1.Rank-4\#ChannelRegularConversion=5 +ADC1.Rank-5\#ChannelRegularConversion=6 +ADC1.Ratio=ADC_OVERSAMPLING_RATIO_32 +ADC1.RightBitShift=ADC_RIGHTBITSHIFT_4 +ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-2\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-3\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-4\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_12CYCLES_5 +ADC1.master=1 +CAN1.ABOM=ENABLE +CAN1.AWUM=ENABLE +CAN1.BS1=CAN_BS1_2TQ +CAN1.BS2=CAN_BS2_5TQ +CAN1.CalculateBaudRate=1000000 +CAN1.CalculateTimeBit=1000 +CAN1.CalculateTimeQuantum=125.0 +CAN1.IPParameters=CalculateTimeQuantum,CalculateTimeBit,CalculateBaudRate,TTCM,ABOM,Prescaler,NART,BS2,BS1,AWUM +CAN1.NART=ENABLE +CAN1.Prescaler=10 +CAN1.TTCM=DISABLE +Dma.ADC1.4.Direction=DMA_PERIPH_TO_MEMORY +Dma.ADC1.4.Instance=DMA1_Channel1 +Dma.ADC1.4.MemDataAlignment=DMA_MDATAALIGN_HALFWORD +Dma.ADC1.4.MemInc=DMA_MINC_ENABLE +Dma.ADC1.4.Mode=DMA_CIRCULAR +Dma.ADC1.4.PeriphDataAlignment=DMA_PDATAALIGN_HALFWORD +Dma.ADC1.4.PeriphInc=DMA_PINC_DISABLE +Dma.ADC1.4.Priority=DMA_PRIORITY_LOW +Dma.ADC1.4.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.I2C1_RX.1.Direction=DMA_PERIPH_TO_MEMORY +Dma.I2C1_RX.1.Instance=DMA1_Channel7 +Dma.I2C1_RX.1.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.I2C1_RX.1.MemInc=DMA_MINC_ENABLE +Dma.I2C1_RX.1.Mode=DMA_NORMAL +Dma.I2C1_RX.1.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.I2C1_RX.1.PeriphInc=DMA_PINC_DISABLE +Dma.I2C1_RX.1.Priority=DMA_PRIORITY_LOW +Dma.I2C1_RX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.I2C1_TX.0.Direction=DMA_MEMORY_TO_PERIPH +Dma.I2C1_TX.0.Instance=DMA1_Channel6 +Dma.I2C1_TX.0.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.I2C1_TX.0.MemInc=DMA_MINC_ENABLE +Dma.I2C1_TX.0.Mode=DMA_NORMAL +Dma.I2C1_TX.0.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.I2C1_TX.0.PeriphInc=DMA_PINC_DISABLE +Dma.I2C1_TX.0.Priority=DMA_PRIORITY_LOW +Dma.I2C1_TX.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.I2C2_RX.3.Direction=DMA_PERIPH_TO_MEMORY +Dma.I2C2_RX.3.Instance=DMA1_Channel5 +Dma.I2C2_RX.3.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.I2C2_RX.3.MemInc=DMA_MINC_ENABLE +Dma.I2C2_RX.3.Mode=DMA_NORMAL +Dma.I2C2_RX.3.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.I2C2_RX.3.PeriphInc=DMA_PINC_DISABLE +Dma.I2C2_RX.3.Priority=DMA_PRIORITY_LOW +Dma.I2C2_RX.3.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.I2C2_TX.2.Direction=DMA_MEMORY_TO_PERIPH +Dma.I2C2_TX.2.Instance=DMA1_Channel4 +Dma.I2C2_TX.2.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.I2C2_TX.2.MemInc=DMA_MINC_ENABLE +Dma.I2C2_TX.2.Mode=DMA_NORMAL +Dma.I2C2_TX.2.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.I2C2_TX.2.PeriphInc=DMA_PINC_DISABLE +Dma.I2C2_TX.2.Priority=DMA_PRIORITY_LOW +Dma.I2C2_TX.2.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.Request0=I2C1_TX +Dma.Request1=I2C1_RX +Dma.Request2=I2C2_TX +Dma.Request3=I2C2_RX +Dma.Request4=ADC1 +Dma.Request5=USART1_TX +Dma.Request6=USART1_RX +Dma.RequestsNb=7 +Dma.USART1_RX.6.Direction=DMA_PERIPH_TO_MEMORY +Dma.USART1_RX.6.Instance=DMA2_Channel7 +Dma.USART1_RX.6.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.USART1_RX.6.MemInc=DMA_MINC_ENABLE +Dma.USART1_RX.6.Mode=DMA_NORMAL +Dma.USART1_RX.6.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.USART1_RX.6.PeriphInc=DMA_PINC_DISABLE +Dma.USART1_RX.6.Priority=DMA_PRIORITY_LOW +Dma.USART1_RX.6.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +Dma.USART1_TX.5.Direction=DMA_MEMORY_TO_PERIPH +Dma.USART1_TX.5.Instance=DMA2_Channel6 +Dma.USART1_TX.5.MemDataAlignment=DMA_MDATAALIGN_BYTE +Dma.USART1_TX.5.MemInc=DMA_MINC_ENABLE +Dma.USART1_TX.5.Mode=DMA_NORMAL +Dma.USART1_TX.5.PeriphDataAlignment=DMA_PDATAALIGN_BYTE +Dma.USART1_TX.5.PeriphInc=DMA_PINC_DISABLE +Dma.USART1_TX.5.Priority=DMA_PRIORITY_LOW +Dma.USART1_TX.5.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority +File.Version=6 +GPIO.groupedBy=Group By Peripherals +I2C1.CustomTiming=Disabled +I2C1.I2C_Speed_Mode=I2C_Fast +I2C1.IPParameters=Timing,CustomTiming,I2C_Speed_Mode +I2C1.Timing=0x00702991 +I2C2.I2C_Speed_Mode=I2C_Fast +I2C2.IPParameters=Timing,I2C_Speed_Mode +I2C2.Timing=0x00702991 +KeepUserPlacement=false +Mcu.CPN=STM32L452RCI6 +Mcu.Family=STM32L4 +Mcu.IP0=ADC1 +Mcu.IP1=CAN1 +Mcu.IP10=TIM15 +Mcu.IP11=TIM16 +Mcu.IP12=USART1 +Mcu.IP13=USART2 +Mcu.IP2=DMA +Mcu.IP3=I2C1 +Mcu.IP4=I2C2 +Mcu.IP5=NVIC +Mcu.IP6=RCC +Mcu.IP7=RNG +Mcu.IP8=SYS +Mcu.IP9=TIM6 +Mcu.IPNb=14 +Mcu.Name=STM32L452R(C-E)Ix +Mcu.Package=UFBGA64 +Mcu.Pin0=PC13 +Mcu.Pin1=PB9 +Mcu.Pin10=PA11 +Mcu.Pin11=PB6 +Mcu.Pin12=PC9 +Mcu.Pin13=PC1 +Mcu.Pin14=PC0 +Mcu.Pin15=PC7 +Mcu.Pin16=PC8 +Mcu.Pin17=PC2 +Mcu.Pin18=PA2 +Mcu.Pin19=PB0 +Mcu.Pin2=PA14 (JTCK/SWCLK) +Mcu.Pin20=PC6 +Mcu.Pin21=PB15 +Mcu.Pin22=PB14 +Mcu.Pin23=PC3 +Mcu.Pin24=PA0 +Mcu.Pin25=PA3 +Mcu.Pin26=PB1 +Mcu.Pin27=PB10 +Mcu.Pin28=PB13 +Mcu.Pin29=PA1 +Mcu.Pin3=PA13 (JTMS/SWDIO) +Mcu.Pin30=PC4 +Mcu.Pin31=PC5 +Mcu.Pin32=PB11 +Mcu.Pin33=VP_RNG_VS_RNG +Mcu.Pin34=VP_SYS_VS_Systick +Mcu.Pin35=VP_TIM6_VS_ClockSourceINT +Mcu.Pin36=VP_TIM15_VS_OPM +Mcu.Pin37=VP_TIM16_VS_ClockSourceINT +Mcu.Pin4=PB8 +Mcu.Pin5=PC10 +Mcu.Pin6=PB7 +Mcu.Pin7=PC12 +Mcu.Pin8=PA10 +Mcu.Pin9=PA9 +Mcu.PinsNb=38 +Mcu.ThirdPartyNb=0 +Mcu.UserConstants= +Mcu.UserName=STM32L452RCIx +MxCube.Version=6.5.0 +MxDb.Version=DB.6.0.50 +NVIC.ADC1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.CAN1_RX0_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.CAN1_TX_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.DMA1_Channel1_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Channel4_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Channel5_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Channel6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA1_Channel7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Channel6_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DMA2_Channel7_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true +NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.ForceEnableDMAVector=true +NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.I2C1_ER_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.I2C1_EV_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.I2C2_ER_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.I2C2_EV_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4 +NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +NVIC.SysTick_IRQn=true\:0\:0\:true\:false\:true\:false\:true\:true +NVIC.TIM1_BRK_TIM15_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.TIM1_UP_TIM16_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.TIM6_DAC_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.USART1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.USART2_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true +NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:true +PA0.GPIOParameters=GPIO_Label +PA0.GPIO_Label=STRAIN5 +PA0.Signal=ADCx_IN5 +PA1.GPIOParameters=GPIO_Label +PA1.GPIO_Label=STRAIN6 +PA1.Locked=true +PA1.Signal=ADCx_IN6 +PA10.Mode=Asynchronous +PA10.Signal=USART1_RX +PA11.GPIOParameters=GPIO_Label +PA11.GPIO_Label=EN_OSC +PA11.Locked=true +PA11.Signal=GPIO_Output +PA13\ (JTMS/SWDIO).Mode=Serial_Wire +PA13\ (JTMS/SWDIO).Signal=SYS_JTMS-SWDIO +PA14\ (JTCK/SWCLK).Mode=Serial_Wire +PA14\ (JTCK/SWCLK).Signal=SYS_JTCK-SWCLK +PA2.Mode=Asynchronous +PA2.Signal=USART2_TX +PA3.Mode=Asynchronous +PA3.Signal=USART2_RX +PA9.Mode=Asynchronous +PA9.Signal=USART1_TX +PB0.GPIOParameters=GPIO_Label +PB0.GPIO_Label=CAN1_SHDN +PB0.Locked=true +PB0.Signal=GPIO_Output +PB1.GPIOParameters=GPIO_Label +PB1.GPIO_Label=CAN1_STB +PB1.Locked=true +PB1.Signal=GPIO_Output +PB10.GPIOParameters=GPIO_Pu +PB10.GPIO_Pu=GPIO_PULLUP +PB10.Mode=I2C +PB10.Signal=I2C2_SCL +PB11.GPIOParameters=GPIO_Label +PB11.GPIO_Label=LED +PB11.Locked=true +PB11.Signal=GPIO_Output +PB13.GPIOParameters=GPIO_Label +PB13.GPIO_Label=PG_3V3 +PB13.Locked=true +PB13.Signal=GPIO_Input +PB14.GPIOParameters=GPIO_Pu +PB14.GPIO_Pu=GPIO_PULLUP +PB14.Mode=I2C +PB14.Signal=I2C2_SDA +PB15.GPIOParameters=GPIO_Label +PB15.GPIO_Label=EN_2V8 +PB15.Locked=true +PB15.Signal=GPIO_Output +PB6.GPIOParameters=GPIO_Pu +PB6.GPIO_Pu=GPIO_PULLUP +PB6.Mode=I2C +PB6.Signal=I2C1_SCL +PB7.GPIOParameters=GPIO_Pu +PB7.GPIO_Pu=GPIO_PULLUP +PB7.Mode=I2C +PB7.Signal=I2C1_SDA +PB8.Mode=CAN_Activate +PB8.Signal=CAN1_RX +PB9.Mode=CAN_Activate +PB9.Signal=CAN1_TX +PC0.GPIOParameters=GPIO_Label +PC0.GPIO_Label=STRAIN1 +PC0.Signal=ADCx_IN1 +PC1.GPIOParameters=GPIO_Label +PC1.GPIO_Label=STRAIN2 +PC1.Signal=ADCx_IN2 +PC10.GPIOParameters=GPIO_Label +PC10.GPIO_Label=BNO055_INT +PC10.Locked=true +PC10.Signal=GPXTI10 +PC12.GPIOParameters=GPIO_Label +PC12.GPIO_Label=BNO055_RESET +PC12.Locked=true +PC12.Signal=GPIO_Output +PC13.GPIOParameters=GPIO_Label +PC13.GPIO_Label=BNO055_BOOT +PC13.Locked=true +PC13.Signal=GPIO_Output +PC2.GPIOParameters=GPIO_Label +PC2.GPIO_Label=STRAIN3 +PC2.Signal=ADCx_IN3 +PC3.GPIOParameters=GPIO_Label +PC3.GPIO_Label=STRAIN4 +PC3.Signal=ADCx_IN4 +PC4.GPIOParameters=GPIO_Label +PC4.GPIO_Label=W_STRAIN1 +PC4.Locked=true +PC4.Signal=GPIO_Output +PC5.GPIOParameters=GPIO_Label +PC5.GPIO_Label=W_STRAIN2 +PC5.Locked=true +PC5.Signal=GPIO_Output +PC6.GPIOParameters=GPIO_Label +PC6.GPIO_Label=W_STRAIN3 +PC6.Locked=true +PC6.Signal=GPIO_Output +PC7.GPIOParameters=GPIO_Label +PC7.GPIO_Label=W_STRAIN4 +PC7.Locked=true +PC7.Signal=GPIO_Output +PC8.GPIOParameters=GPIO_Label +PC8.GPIO_Label=W_STRAIN5 +PC8.Locked=true +PC8.Signal=GPIO_Output +PC9.GPIOParameters=GPIO_Label +PC9.GPIO_Label=W_STRAIN6 +PC9.Locked=true +PC9.Signal=GPIO_Output +PinOutPanel.CurrentBGAView=Top +PinOutPanel.RotationAngle=0 +ProjectManager.AskForMigrate=true +ProjectManager.BackupPrevious=false +ProjectManager.CompilerOptimize=6 +ProjectManager.ComputerToolchain=false +ProjectManager.CoupleFile=true +ProjectManager.CustomerFirmwarePackage=..\\..\\..\\..\\..\\..\\..\\..\\..\\..\\Users\\dtome\\STM32Cube\\Repository\\STM32Cube_FW_L4_V1.15.0 +ProjectManager.DefaultFWLocation=false +ProjectManager.DeletePrevious=true +ProjectManager.DeviceId=STM32L452RCIx +ProjectManager.FirmwarePackage=STM32Cube FW_L4 V1.17.2 +ProjectManager.FreePins=true +ProjectManager.HalAssertFull=true +ProjectManager.HeapSize=0x200 +ProjectManager.KeepUserCode=true +ProjectManager.LastFirmware=true +ProjectManager.LibraryCopy=0 +ProjectManager.MainLocation=Core/Src +ProjectManager.NoMain=false +ProjectManager.PreviousToolchain= +ProjectManager.ProjectBuild=false +ProjectManager.ProjectFileName=strain2c.ioc +ProjectManager.ProjectName=strain2c +ProjectManager.RegisterCallBack= +ProjectManager.StackSize=0x400 +ProjectManager.TargetToolchain=MDK-ARM V5.32 +ProjectManager.ToolChainLocation= +ProjectManager.UnderRoot=false +ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_CAN1_Init-CAN1-false-HAL-true,4-MX_I2C1_Init-I2C1-false-HAL-true,5-MX_I2C2_Init-I2C2-false-HAL-true,6-MX_TIM6_Init-TIM6-false-HAL-true,7-MX_DMA_Init-DMA-false-HAL-true,8-MX_USART2_UART_Init-USART2-false-HAL-true,9-MX_USART1_UART_Init-USART1-false-HAL-true,10-MX_ADC1_Init-ADC1-false-HAL-true,11-MX_RNG_Init-RNG-false-HAL-true,12-MX_TIM15_Init-TIM15-false-HAL-true,13-MX_TIM16_Init-TIM16-false-HAL-true +RCC.ADCCLockSelection=RCC_ADCCLKSOURCE_SYSCLK +RCC.ADCFreq_Value=80000000 +RCC.AHBFreq_Value=80000000 +RCC.APB1Freq_Value=80000000 +RCC.APB1TimFreq_Value=80000000 +RCC.APB2Freq_Value=80000000 +RCC.APB2TimFreq_Value=80000000 +RCC.CK48CLockSelection=RCC_USBCLKSOURCE_HSI48 +RCC.CortexFreq_Value=80000000 +RCC.DFSDMFreq_Value=80000000 +RCC.FCLKCortexFreq_Value=80000000 +RCC.FamilyName=M +RCC.HCLKFreq_Value=80000000 +RCC.HSE_VALUE=10000000 +RCC.HSI48_VALUE=48000000 +RCC.HSI_VALUE=16000000 +RCC.I2C1Freq_Value=80000000 +RCC.I2C2Freq_Value=80000000 +RCC.I2C3Freq_Value=80000000 +RCC.I2C4Freq_Value=80000000 +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHBFreq_Value,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CK48CLockSelection,CortexFreq_Value,DFSDMFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI48_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPUART1Freq_Value,LSCOPinFreq_Value,LSE_VALUE,LSI_VALUE,MCO1PinFreq_Value,MSI_VALUE,PLLN,PLLPoutputFreq_Value,PLLQoutputFreq_Value,PLLRCLKFreq_Value,PLLSAI1PoutputFreq_Value,PLLSAI1QoutputFreq_Value,PLLSAI1RoutputFreq_Value,PLLSourceVirtual,PWRFreq_Value,RNGFreq_Value,SAI1Freq_Value,SDMMCFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,UART4Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAI1OutputFreq_Value +RCC.LPTIM1Freq_Value=80000000 +RCC.LPTIM2Freq_Value=80000000 +RCC.LPUART1Freq_Value=80000000 +RCC.LSCOPinFreq_Value=32000 +RCC.LSE_VALUE=32768 +RCC.LSI_VALUE=32000 +RCC.MCO1PinFreq_Value=80000000 +RCC.MSI_VALUE=4000000 +RCC.PLLN=10 +RCC.PLLPoutputFreq_Value=22857142.85714286 +RCC.PLLQoutputFreq_Value=80000000 +RCC.PLLRCLKFreq_Value=80000000 +RCC.PLLSAI1PoutputFreq_Value=18285714.285714287 +RCC.PLLSAI1QoutputFreq_Value=64000000 +RCC.PLLSAI1RoutputFreq_Value=64000000 +RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSI +RCC.PWRFreq_Value=80000000 +RCC.RNGFreq_Value=48000000 +RCC.SAI1Freq_Value=18285714.285714287 +RCC.SDMMCFreq_Value=48000000 +RCC.SYSCLKFreq_VALUE=80000000 +RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK +RCC.UART4Freq_Value=80000000 +RCC.USART1Freq_Value=80000000 +RCC.USART2Freq_Value=80000000 +RCC.USART3Freq_Value=80000000 +RCC.USBFreq_Value=48000000 +RCC.VCOInputFreq_Value=16000000 +RCC.VCOOutputFreq_Value=160000000 +RCC.VCOSAI1OutputFreq_Value=128000000 +SH.ADCx_IN1.0=ADC1_IN1,IN1-Single-Ended +SH.ADCx_IN1.ConfNb=1 +SH.ADCx_IN2.0=ADC1_IN2,IN2-Single-Ended +SH.ADCx_IN2.ConfNb=1 +SH.ADCx_IN3.0=ADC1_IN3,IN3-Single-Ended +SH.ADCx_IN3.ConfNb=1 +SH.ADCx_IN4.0=ADC1_IN4,IN4-Single-Ended +SH.ADCx_IN4.ConfNb=1 +SH.ADCx_IN5.0=ADC1_IN5,IN5-Single-Ended +SH.ADCx_IN5.ConfNb=1 +SH.ADCx_IN6.0=ADC1_IN6,IN6-Single-Ended +SH.ADCx_IN6.ConfNb=1 +SH.GPXTI10.0=GPIO_EXTI10 +SH.GPXTI10.ConfNb=1 +TIM15.IPParameters=Prescaler,Period +TIM15.Period=200 +TIM15.Prescaler=1600 +TIM16.IPParameters=Prescaler,Period +TIM16.Period=10000 +TIM16.Prescaler=1600 +TIM6.IPParameters=Prescaler,Period +TIM6.Period=1 +TIM6.Prescaler=1600 +USART1.IPParameters=VirtualMode-Asynchronous +USART1.VirtualMode-Asynchronous=VM_ASYNC +USART2.IPParameters=VirtualMode-Asynchronous +USART2.VirtualMode-Asynchronous=VM_ASYNC +VP_RNG_VS_RNG.Mode=RNG_Activate +VP_RNG_VS_RNG.Signal=RNG_VS_RNG +VP_SYS_VS_Systick.Mode=SysTick +VP_SYS_VS_Systick.Signal=SYS_VS_Systick +VP_TIM15_VS_OPM.Mode=OPM_bit +VP_TIM15_VS_OPM.Signal=TIM15_VS_OPM +VP_TIM16_VS_ClockSourceINT.Mode=Enable_Timer +VP_TIM16_VS_ClockSourceINT.Signal=TIM16_VS_ClockSourceINT +VP_TIM6_VS_ClockSourceINT.Mode=Enable_Timer +VP_TIM6_VS_ClockSourceINT.Signal=TIM6_VS_ClockSourceINT +board=custom diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/lib/stm32hal.strain2c.v1B0.lib b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/lib/stm32hal.strain2c.v1B0.lib new file mode 100644 index 0000000000000000000000000000000000000000..f628f1de70570569cedd96caa828fd4f314f5bec GIT binary patch literal 392986 zcmeFa3w%}8nK!)lJ|`DK2qB^cM0*l0hHy&)Dp;x~=Oh6%n3w=sOUpS)PS}Cm$VIT@ zXhN}~rBpKIE_EoDTqIIa_*u=sN<2dbcrtegv(>Xw(DRo}H|FbT8 zuf5McfOGq`-|t(=K5IRf^*qmd)@AR#_F8)vuZs7!Sl8w)4Y@8pS_c@-^Jrg|H#;X=kb>(82hg{Qe%w$4j#th z>)C(G@!7YS@llRD8kupv zJ|6F0!-D5HvckR0_qcTy%kmyufTN@9Dfh9nmSx>(vaH>^F6{Vf7t7L*|M8D3>%a5( zDaxQ9e}5~>`Z>yUAxG-_EGzTTbbDWaqH}Fmdp{G&Xm@WS+R@#zZ9`9Myg$L#HLY!o zcWp_mk2iNDygaOGO{AeW(bpoVRSi1yUnsh-zjIlo74O*GPKK|ks@qH@Sl`~VO#&@; zdUe9VS0_5+w{woBfxezZSF6p{nCKhmOxPgzN1E7meLb8ou!9(DdlTE4NH+AgcXP4T z2|Fj4HE3;@ut@N8UfnR6w&gSlqqzz)L(*;df(wF-YvLUn6TN-y-Cas;W6j33)e5NA zfemY`ca$p%0Tnt>$${#~>UGf#n`^qLK>%p#NF;jJb+;yTYIS?xxyVlD{_b<-^`UB6 z<6W)Ix1U3Eznh`yQ%%v@)tj3dtJYQ4^v3&y!4fOPu1j=w_uk&LBi_@~-nAtX?-K1v z^2kD+n`vWXO>JaD?dFZ$9sThwiKdo#2Si1?yV}~fa1Tjgif>K(7He&1Pog#6)so1} zw!XK$v(s0Quw07MHAr)PC?d<+`l_yYNB5Sd9qs)sR;0TdBSEi^fXsYV)luH@cqRf= z51}?ou&&9Diz$~aXt5|PG<0`#)OPne8f-R6 zsktrDC58!G=;pQSZ7ve#hM{$H^|~ry<+>`89PQ~4mH>|~)#k<3^!9cO?~x7;MdKYE z&2c#<5mx2#C2*lol1Aj_ku|Ek=+qnI9Rs5MlH9e8H?2Wi?~v6;sJg^$iH`b#{`$6? z+q+u3cce*$EohNZE8f+W=&(hL7IAa+YC*Q~P>H(0=|Ho=RpOeRo1vn;xi{XAkw#XW zWcJX!=6lE(`&^|1d2QF$L`#37RWt`js)I+1N=IjG7haKC<-16(W}#7hN}x>1RK;5E zn+6gCiF$N~wvP0A0iU<(D!p~*!?VnXr>3j5zO5AF^j(D%$mE2gj zTQqjwH`4v>+oT{;4mYwAdGWQ{lEaj8UayFSK~a?(7hwkTiv~* z%RVhct8R40C;}RH*0#5Gm)8z-bhw;GwDmjJ#oIfYyLXmHyWzJ)eVO`&r z23%v%pshRKrKd8Z5Zjc>s^;!q_o(0!QGOnJg+E;wS#b^{C5Nx0_(?ylSU1PFB{uZb z_I7tR?u6hpditnHCDBhB1Z(F20`2xGc|Bybh;}-0r77Fcm60SGYHfRmI^hXDbgrRR zO;BTE`#_?vpO@1{it^du+CEOMYUyvkO^l3`v#PZfb(iSt!`a_v<#n)rr<7`=F_75x zoan>lU4nOho4&Ts7A2dKP2ySCw|Bxwba5RG-+Q!!S5zj7+~L;1jmN-#V|RahTYC#1 zy=`IDi8z%l6WMdxp~6FxbDoe0=R6@C+n4BfP&aN|i_?6fpDulS+xu@{-P=7t*IwKP zFVR8DA*Jyq2c^al9Vc!7vKWJ z87B$Q`Wb=Fxz~o&`GF9;fph6Lq?6^TcztiYtFKL7rVyj2G=%c)wM59!p@{@HI?YZZ zoHkZ-%lfs{#zdLx+Pg%*(SdrNP;ll9bg#QQ8JkT=KM`*8(a7w_w@@1abpR$X~ig$Sg_ zIDxctrw`SFfnQYET&_V^Fl^|e$pg*cIyYD!K}C94fJ^79iw|_QSehVIl~bo&8J+z3 zjhs+j+cD5*MdK}2qEGsz0b{UptLMt&as~v|W9mY9mQDeRwLW4u5XTbxlBRK>%f8@n zk!5d7qpxmQTkrHT4r$$t!;Oh}YeT!dS10zHF)SurnDyOTwsg2rSzFlYTkw5HSe-fa(Qur z(W`;v*;ndRjJ18$iQC#+5=0QwU|Qjt65H)6amg1>c9C709J(s1ytVcSS5!T-@SaPy zmN|V4B9Y>9)_bE&6d!5+%9JUZE+?-d>RH9*Mjc&fcInQM{XCr@TNAfc&rq|`d&(oj zYa0EqLdN=?H1psZXdTBk`V)C!GGyem4Eb>B>b{O9O`>rAMkG2jXh93lpu=^lCiy_v zH)|4hhIt?`+KLmgn48e9+I3=e`gy=Iq^03qVF2Db&@2c4;2YpSkA4%BSRI{`sZ zPDv-Apstn=`KSl97&RS0PbQQY(NOw(yF1)-uNqxeOS~Uty&ZF3y<60+hL9}%8_CEZ z1Z-?=-Ov=#@? zqlYT83T^aDWYIv=MVyCAh~l&EkbnWSzY+5)UG^oaCy3D6k8`tSrn{~M_tBzG2d7Z{7ve$L*;Ma?|F4Q}dGqhx85WN=Nv)q%@CRAi1 zRQeLuY*=4ifAftV8amu&ILUiD5>6!V`E*C1-P4aY_i`6^W7KsiNnm|ni`J?LL#Kz^ z`}hM$`)L>9ImW}gE?V!wAorSR-3_jsz%>9@;fJjBB7F_=(=94A+SJ4=nJm0<-CD2P zxZzDrUN4}&8xpMz7eEYd7e>@gM?Tp=>*|`S){2%7?M};TNF#{Rh-TOP%)sq5 zf4U~0{-&8J8+22R<^o4sofogOtLq_QpJ4Uz9HdE_kN=dsXua~kuH1zctaywK7uc=c zTd$IWSPcUSx8_|3MuSJ$ioGjGf;zO`L#;z_YE06cW- z?h)n|;_n*d+)UYSj`w!?_(zfJw`CyK?CcSbR3IZ03q8?t({5bt+`Tpe(C-up*6s@> z*@IDj!jgj4?#>$rI-BKW5V89a?Z(3C{TcGP@Ol={BnN3pzpEfDzbC4W_s7!;Oca_} z$)wtucoJpMCMnjhUAH-c2hEPtY>e`pjj-pZcP6!&Mx?5{H;yrzdR+rb(sJ@Rji7UM>2+LhYrrUR~gss(oM(lkO=}H!YTzmZU~dtC^4Kbv(vfca!R0ca!yfA;k8Zrp zrqz8k-qSyT^;EQWKvuj&sT#9u1=$t1J~>CZ9FoeFR?o^F-EZ|>3Eqs{jlMXqyn~f%3aADg zq{noJ;BPsX?Ha~hIrQrCoT^AI7X575;(4@5c=T#Ms?=l{d_fo2E^2v)$W-Y(1aUPx z*GdqscWs3aEA>vdST&;973fb!DI){Def?t2)9r3q#EcEwn^&t8n?z@5w^R>F%cQO` zoFze2U}1NCv^UYlpT+RbTC={<#|yHE^aMjZqqAKpDC^f&tnKO<5YHP)HlJ`4G#=UKtH!+~r^dY$cL(-TUA@>#q^xLJs`|WS=yW?Aezzg2eWhEYQ(PwL z1XAQ&w32t^sYk32anocM?e6Rx=y&yV)5xp333FAf5rZMh|t%>5@;&86v%j_%F)1qS7P&dqH8MeeW1=(O zBj}nqz6L{{Io^;U3fCSWdkM{JIE2;awsMzR}WxK7cD20)75orwY6dE z20HrN@eG)z>-7PR3)aRd4!g%Dj#5u3xx+X{K1p&Aibb_Koy(0&f3D-wVGlF{n~8g; zZ_DC&((k-n#;DFKkmryC#)kNSTuaTlff1|eopJ+ZUkY*_XSIj}D(5)aI9HkzUC-2< z>}e0E9FmgkaxoX9DCfwm9tXnAzVxg6f7EZC!2L@oA znTE!u03cyaW$pa~RHo~{**n4vru$a!2 zO-K^yl5{iXGBXp`oSRs~*4;wO_A7+9t$1sTm`SDu^p>MSw~{OT0@cpoM`-0o_zcSc*j^j3B}&r1>%y-W~wpajufqUI}vr zs#2B!D6we;Y_MLN3YNdovz4-p1%Lf%3*0c&Rpy^Nx+dbMtlaF05LzF_D2jH_HZESn5VKZH(Id)rsbT zE$grZUn!v{txX$k5GGR#vtf9)VzWHi!;{WV0-dlt6XD8CgsUsP+lhPig+RHMUI10OIgJY_7uSX+j6p76 zaSR%rV>S%AYIAiJW~m$;JX)z-?J`a$xcr0GOq0sIv0J@zRV-oj&LUy$5=Bvwo!cSu z_qTUmMg2oMjV^*L;3}?ENZ4c}ui{M}tm0-m?mEy%4u{=J& zbu8bxbF+obhs&09FZG}>FlIt0cKT5;1p1<}{lFjJ+n+&Dudn77pfhE--Csp7@cvm^ zRU1GJ6gB+N$T*|+tGu;$d|t#oyw73MseX!`KK3H_ebS%!}z9pwt?ZeGm zZaSV?XgXH3DL;I(x09oU1DNnrmCo;$H#=8ryswCx(!Ty)+_|9wZmVc6r$Mt9d;V`r zv@UVD+xuO3kFfNCwzCfn(;0PeX$T&E$yjmKRaY)AUs+jR5en(=YO5$Ozv`;1LZRiA z%j|2*yK3rc4Z~n67_5{z5MxhF;*_lAJSt_2KplLh;4xM@w z93T^rX~v2vZ6Iw_#m@fv|DI)`!57&8p#@bMw7Oh>*k8QIvu{SHMp7`7<}=?cL&3;S6a&XNmlkSj_p>k zcF*dp+8NJLiLz?h!5-ww&5` zY{!=RP+NCzs0Is_T3ZvXp{tfutO%{|?(VoI6z}b9>A(Wy(5J6VEN^LvmzRGA??ZvK zcp~21&Wvl3j8-lwU&*psu!A?Tb8+W#mOUkBT`rqs=4BVKX-1Jb-MpB6%$Q-!G-er> z8ncbd10}{>W4xnkKF|RRY;2vU~hY1MWHx={D14xNA7n* z0P@~+(es$>HcZ$v&tXO?zzW!3yZ8${^dffHMW@9N$_%t zQJ%1bt0{)v4H8~YG3>P@+(9wy-YMZbD2AO6NcdrjVb7Bi-cK>?dO^a&6q7MadJ`Q> zFlH@D>}+q{xda1V{}P%n67$%c>ctVvmf*^+6T>cB(%jd#q)(i-X?~@-r*CuXKxgOe zoBJ_iiK+1|iT))m#OR~xT>08*TFW<+>pfDAiS|S`&uK&2w6?FbbDJ(K;4V0qu_z?t zZp0>(-u7lZqUlrf%<9!#zGdN4)F>!_e&7@(9qm&^c;w=f&4u;JrM)!E&mE*$f6rDX z9`$alC0*V9i6yIV+_1Q>pWd2dyPYZl?V?3I{N-ZsYO=Viso)aKMWPyZ<`)_sN1qI6 z%){uj{|uZ8H0DuQhJ(^_h~WK~@G8h5hP?`emyi0k3X1O#5Hy^HC7~2!#u}s-;vjp7 zkIq$(GB34F9aqk2VR$K%R7NISZ(`80Fxf# zp`hgb3Ta*5KFz*-$w&DfgfRTu^?M9y46k-jKKc@vba_ueULm;1K03Xq^7aUMwtXLf zMtbBa$hNP;Bkx(wK9Z~CErkKPedC}hn~=2A^8}x*cLFrhtIDGMQVc%59K)L4i@>k+ z9v0=W{X$02HGvAshF3i0I1G7ox*@;N)sT|+gpg<3Hybe7r>>ZkeUE$OB{lm#rpcRw zG+1r><^s_BzmoTH@aW}z7xF^Dk$rSErtAZnfw$XqUWP3=G6a@-D@p z|A>%UP+%Pr(AlF%#CMAV5G%gD9(f_ahc!OszdgX~ z<)v%h2f#<|WdROV-Y3C_e>=PjAdG|bsdhzvTB<(~!z{-6<}fNM%dZxb7_q$b&0#c< zBAhms^QaW}ZZwAx2#Hw<`prFHV0J>ln594<`}Wg)KcB&vWc}tquvX0|)Q^9zmswB! z_W1GrzdfF!TvHd-r;MzEW7c!^sk7z9wYaRFM|hPZ7-LCeUTN)qTedzQF!)T>iBk5; z36mjr1uHS)W_&2VD{jQhSXC?%8;b36W>BPUdVbO(Ev5MrgIRf2VRdfI%L5u3s=!kD zD4!R{%bW#l)&grNk~iX%npxaG2ll_XD8@pfB*IVra)PzQpJjWES@GF34hE~)LGBsM zmYn&iTY8W%}k>$xAR?> zM%({P`8-I?Dz(BX%s=wB9>m;Qsl{@#kMLG^>EzO1|1?0YPPRO1zvaAK)M6a(6Fw;M zRpW!(^)f1au?J7%59MRO=W}s%Pp;o$~up2-Hvr}LJcgSW_|#|zWBRkwq#Pj#5;T8An9QDCpW|7@7*@ITug-M8hC zpQ#?azVU;R-4$-ed0z#;dDPEPh1fw|^#}ybd(Lyw)!mq)PiFt(LQS?MQG(_i%wUqP6%N3v&ThWZ0G|p|58Tx#%s{%P~j+u21fdb@|-$^PCYztcnS zVc&Mqdpz_$w%0}P^U&{L=1Covj_)0hxnp|g}x$oLfS*;&k{U` z$d^N+$iI^fNIIPZO7L8w0U1di!A0g}>}3E1)A_W>EM|s_K9AAkKcbi7C@~kXXQezE z`AW>i?5i%gob}86REzi_DemS}+n_*t3ddyWs2C8;3^T-6j(9%eyn3`_iW_k5COU?hTB6J0rVKVy zD1&Wt5$82=kd;xTB9zHVMAAd7OE-u)2+~LOR1TOz8371HCq5fbjRAr5a=g+DW4-p1 zUx|+%A(4GlFH~*{Wkf_!c94Dw^xTQ$=554*nCPUE=sZ906ui%+%H+gd88H!^CX6T! z@rad`$at=d$(aacr81^Ygiy9f#!F;eF5^lWFPE`A{gthd@HH}CC1X?))gP6EOre-U zS(rzxj4BVItXjsXM7lOJ*La?%0Vb6uoI*{7=%{-B{B4tjV-)8y)-U0m6vKJDCA^1X z)aSzz{u;$_>f;iAf?^o^w1l6f81*wE;Ug4JXDlhArV;@SG8a+LK%cmIj(P9Dq zTu{Oxicv3%BwS80oU%&7VTwa2pM)DIMt$-5M97N~JQwqClHNlx>hBH-4^mvp*j@=g zKr!m`Q3>y(81?$3g!fa7`h7vd!xWb@_PT^eC`Nt1E#V}^%NhGX!YPVT{~t=28os## z<)@g+PchoVYzc=bM!Q%f;c|-6K2}LMOmP@o=Nms4n9KdLOSuc}0`s2Z z<3sv;^3Nkp`=S!(Y}FpVXUZzSA|(d~`izwJwWjlA5^eLN<O-Qm?opU%TAJn3S#Te=kJ!{Xml#aG2LDMY6gUmBzJ6nxD^ z1^?wgm3;k01^?wgm3%Em1^?wgm3&=B1^?wgm3)l`_O3x5|5?V@YgF>z3jQk=aEKKg z{I`PtF3Y%j1~$?+&#>GB3qSa8CI77u>GS2|D@2y@-%9>lA%4%7ubk`Szm@#Ag8$-@ z=z_zRY?`BR!Uwp1Y|eFHTq^N^%Na&#u=9Y+Dpv?f=vRone7JZnLj`5u za`5T$UVywXm`EOOk8OD$6Y^~Po&=5b5)TDs-$fpIA8PiI9#!51(z<<516DR6X{SFe z_-wt;0w%qaaZpftX*NnPM-a<{m0xgcVe5SXXoKgUn z)2^NaUbpWK$SVb%{8x-a$@>%V;or7Ttu-MY3d+8(f=QS6xMtrR$w&VCt&nH?ZxFCw z{r=h`?@7&n^E7#XE9BYs?FCGFh=+o*@24JlFKG5%A^9lZ3LIdy?Ryvi`9%dKkIol* zd0&CN5OCzb1vr%dsBb}pZ6Dq1lOE!spyXj1!zJ$*ntcl;ALV;Wv}fDCS0GP~1t8nw z#uJ`)e@yCKOiTz$@8h0!|AD4=iR2@_U-sxtX3%@LNAI}QtIpv{?~q6DxTd#4)7$0g zZ#36I_NV|d53Qbl6a-9s>gkcv8v|aiw+}VFRHwv8`2slML6z-inp06@JkVSCB0g#_SL0B6=X&(cg*+P9Q~=1sEWu~%T`u*ir(H_# zCE(Nb=4*Oss!-`&0b}&?(wvZAzg!~tY`trwUQ8?Tp!Cu_uda8xruUPYUUGu2m!2*7 z={@Z!FU?IME1uSgp!A;bly|nKHw;!)-orwkUBA?R{Ph0Nqqj%ujd=7v@6kI~(;LXp;q8U-sy&*7Vj(K5CEc9=)`-(64?sd-Q%N_2Tga4@&Q+J$majy^Y{h?RmLJZxG|F zpWZT$-WlK{yVnb~c6sM}^sd+R(xVxr_cuuB?J5L$e)mWJD){ViW0llP*Ygxe9)396Z-=J$vzp#+7@+IzfIPqYO$a`_yn|A2%%e9BKE1sCn%=mk z_kViy?#ZC{F^}FyrQQ~g-fwvH-l6Gj)%33P=%wovzw*-lGQEE3*)p|{Hjmzg9=*FY zy<0TBf8!Y^has_i;^c7kE`UZibWf_E!jkpWbzX z&n|CB>h1C9T?;XW+|`^{)8VWZ!WgU zEydPKK4fJ}D^_A~EUgonTnRE_NG zEPpP<*MzfBGO>GNJu9~MSc5G4=pL*7^l0pn}Nir@T_BuqZCuQQw~Wcw0H z#0EeA#5p>VKU{YrC-9Tg zslEUt&WgSkyU+TfB`nK@WlJEXZg|d}4^Nbb>c&35?BR(ONodUfE35iMwmE0aG)c~D zvAp&l9yg{=hu#0yS27mJKl0vGST*hcke#Hfz$}YKQihq8jHC(;BUG3y0hAXnX`j5! zD4Ua-YMP_})NXuYRy42Wu}-6;`J`bymN570Yy8DZanTRe+mvpBV{Y6$5! zPV6$PQtYOo*h`jqyf9#-28&-p8n~*LVn%!S$vne|SG5CQRTUpXyt8U3ZfrGDsbZtK zYHM-o?6j)pAs!Dk8{1}vjh3oy)529PL--wPd1+ht#Ls&ljK0)jbk*~BRGh7x7B&mgx{gIm+<>i+sMSe!tRqr#xUZMiN|I7aisUl^nRqD4xyD)l%(z|8b%ter2(zQ zKx^sAy=6EjFq&(1pPUiSjX5p;mG@@APt@+y_JTZvUSjRCKCjjNhLJC@B|j*9?YLFc5j5NL90AcFe3JB zWS5@)X?nlv!K!>5JkS`o{}}`C$+!=_dpM^)g*ly(qLgXQIJp1CJr+w%VMggCqoU8l zF7$b`d`~P8%H`|+>75#+b2vxo4EXAFb^?etskhHU?$1FhoD(?mF#K(l8lz^Y@I@m; z-WN48;{YoLR9N^T%5&P-z9-5~4fgCy?CWI3!$GpT`e3p%l*-1)5wd2Nm@(ph$-37F z9u<9LO2uP|AwF_ZDW-*k6+7{q84rg-)%!y_VK&SX_1+uLsmtY z_Kgf_<7j{JDLdRVR#Td!k19 zz63^S=?lm9#qXt}L;FW2rlXfXdpvjQlv-mn_ljULWDTQkR*nX*AbG{uX>?7bV05Uq zYc@N0?E%7l=`Z%ZKZ!jNS$wS6%C%NRPGaN_k2Co8uvIu7?w&dtyVH6u7kfMMj_&IW zjSH_22LpV>Hqb{7Tci>CFk**;#*uuq4HlY`q?Q)~-3aCIbP#FA>ogED_P_XU>hmu9 zt1hXXQai}cIL9VfVV+eM{$6D2NKS1(Y+c1|z3nfCFWnzmc#P<|R%!T&$cfRji$C@c z&zu^(YthIvr`TPU_#NyHj~<)2g@wll!-o+co7lv{sa$p#asBvU?8>CM_==Ii#fueJ zIdKh!79@GDR1loF4hZc*y#zwAb4W;IoDULurVGyT!4PrQ!&{RjhQ$bDh5~?>v(SM; z?h8l8Ag2q9Oz7Ff{`HsS1?q?Yv3`I)knh(M;_XK!mM3|C7>-!E3rbS6%}6Y-Hfmva zSIMmC50A5{kyv0fV&QB93XNkIAN^LRF{kC^6r5utR(C2K$i*1boeBlau>g4LQy~Mg z4u*@T;oOj^SE({(Zr?kf3t3gz4>a4Tk|XcAS~|%SebhTv^w?v?#kB>z1*!3(CvCjI zHAx`NPo2OTCDt&}kOEY|{fT(^y~!1`i-+OEX*8w`-()SUt-^Wvrr0RoM>ZNWkB5y) zuC&$7t_aCqjqrX=R0?GUX*H>nltid_8Qt*caU{Pw&m6quEtq-`%uEL zCR?vrmtrJ*Fem3I(TmUr&y4=qx;OaiBSW3E7iuUm)cNC}$UW4_$D{<8B-_#8Rt1T6 zHMo_y!p2bICB#AFC7WB&_uFF-#@%^WC)Kzs#-Oa)TYgY%g*sou9x?-0FAq%23z;~_ zLC0C^Kvr$YdW=hdEI~C{XxC(6ve;TX%`M%HastzNqfR~TY6(DzwlA7F=mZb&^d zw4csS1y;SaKWFOEkKyViA0yOoHXnb+SO?pGn+mn4QQepN9uii#8_SYSMh1$J1HH`ZIsxkM- zMdRU?T+}dYx_or9_37+Ok0M<(WAr{)By5Q(TW;dEWS!5J7;Gue&W8nqY!V;I2XV$w zmJWiN%9?WYV;IBo#5k`}X=Fo5IGsuQV93c$;~es5UkvGmtY{>*t?OXc7;|#0!HMs9~ zUi?nMnc#`CD5#-XXmc$32l3JOg3JHS3NG9{dQI0gU6ZXtCwDi0<;=HFzkG6cNB7B} zN56mO3#Zt^MYZ*(&)%7Pu(kGEk>L|L1^M7c{>U|Ld6qd=5J0Yuht7QK#8YQ>o%&qY z=epQJlC!8*~iPWz~-5XMZp9m*6ZLefZ4dRK^o*VeY|KP(q{9 zOkEx@Qy({t`E1@Fh0XUPxEl;5vfej0Tp6uNv4OmWD-PC?!oEf%)D#_ zxYN5UAB+G_4fd`WF_4d$4@Pj_FoM%DPBu{a6* z_Af`ufT#OnhsKPVbk8jJu+!c0y^|jMty%QoB;)-m<6ee0>^;c-Wcva3C&tR({8C8C z(WR#bx6h2RVpf7SAIh!e{pldh{nGs44Aq%bpL)jWDa+AQOx{zzVm)jHQo%qll^eWt z=B1-}W8Xiqx!*p;0)KgWc>Q;4>c{?~=@MKYpS>e%;o%e4En0u<=kEqmft%x7w(t0< zMR&&0aTd5uYwLk`1UKq3pPhJk(3l%Uzq%-O@zj|k1t}x=#z~_o`2H)w=-BQ6I0sDB z4J6Nd+xpJ&FDJ6b3bLMz<{uv(C>YDio*&(l{GyeAYVcy}8R!wGFB;3AntSk@1=;Ai ze^x`1vqs;X*cV$CJv6beyf^vg#N#~uczH)s*jEY(M^MIzXmBh)I42q%4+k!nv}kIu zZ-$qi+SgZL(}(+V)9A^*pT^L8R~@nHQ`rRtV-E)dXM(4XSW_%Y|LCN#!F>Pjtc6?i z&jiNF}xa{+Z!8sSjCjY@rma#DZU{z|+D8|v2Jil+qBXh^H zvws#t$x<`2C%4a7VvK&BEQfrLPPre>(V7xE2YOC!~;wzmKE3VD|mS zz2=_4J;5(z-JQKVCsGj7eefaYnQ_0d$Gj)-h2Y&;yR%*Ilzbg@C0p0IM#JlNKE?6= z?~sgvru!FDtS*?=km#~@1J>%t#Y=hha^PhQ;GItI%=|*&?%?h$)TXYB=5jwOtjjOO zB(zt)ZtERTpx3{yi{_raFi@_rf(j&q-=6OoG%0Nd7^4N+^KH23IU1Gb&+}Nyh062L z3)s(H^a2kZ?|O96=}hH>0CuLm=%Q0iI)V0lKk1^Y)oX$$z%FB7chN6%G9wkh$?`rI zz1Tya$8LAg=XvN0Sdq&=3q172?6zrYw*yU*eO?jxmi+j1=vRR3m1K(C;z9|PhIp+dFY$iAs2lUI{N*_+xCJ zi$BJ`4A?1EjNJ*i(asgKQ7S`#?-{PUS@jbc@vdu~I{2lBl#v}YQI>*o+YFcMW zFpWdBXZnBIwu|SGUzc<`#}r}HA*~-F{#S9(p67`y0n@pJ-o3g>@(X#FupfBjRe_K4 z)A@wn#kv^d3&A4)Weg^9n9d!v=Xte+>6}qy&SSd}6F;3Fim>Nd?a_Um!;9J9OL=QJ zT){4dzlfj4|045BHXQ)LF%GX}Zz3ib*+Bm!i^%fPNKs@~u}6s@13g#!F$PWI7v#@sfiH6DYhrUC zPX*$qJ<}=>{I{O^PP{aR1mD_oF9b<5nk!T ziB`#7M0h0^$hndaD)}DoTPVhYrq3d#z240f18yUH17lqTBYp&N-c9&HpuNs8kzEew zR#J@N3oJaQk%eFiv=`b$eEE6~@;%WiAE%=b%1&O+jiSED-c~T!c9YQvW%K1;bPRXj z1WbF(%c#C?71x@1Sh&+hFpT&D#h+p9S&Cuj7~;#RkO&vD_xe>BPVMG3#N~)7lu=D29_KB>W-8Xg9P@pY(+&MtfN$;V{K$FY6_I3&p6E z4hi>AJe#pS5~lUmw1@g@5`L885Z=)*;U_6Zy^`Na-wPDaW$cKAk5Pe=ASHh(fFTr>t;T05@W}e_j(le`zDc%Oe5NzgmM;1#p!mEo=dd@9dGJ2F#fYP!yQ8DFyH|XlH(h|6 zY`-DeXLB?OgR$5X+lI}LxAE`tI`T47J!VP1%o5xbPj1@%NfOStNn7&hJFzoJ(pg-d z)d?B$`fS=J#UE+oHf6wmIPoD)zZO6YaJ$C9%}hsUGSc}jo>N=OkJ?A`GU=xJNc8r# zcX#nm%Q`a10zYB~J3P6S1r9nxKG{GWO=6p$tFAKeWRM6^_=>aq6r+zcH{H7rn+&&i zMtk0*EelmcpHbbKXz5S1-ZYRHNYulDZ5`b^qWHF1Gre)!&)3Q!b&1;&9rXkK^=&t| zceQGn(uI>xT%W}~m)wuc%sYBdNB;#`&6}sq>6lv6)mq=y6z}ZmXz$wML-&?;*#+=a z+C1kfZ&g>kqkGHE)vHByp3~>3&yDepfyDWk#22u+*7NPX=KZt1FW%fCr8>P<$9kG5 zXmpeRAOb6I`ST17~1!dwVVDj?OJ+cal@2`NH1Y}qe7U7x= zmv#L5o$Mh#GULyLJbS(F1Yp7|o0YupdE`|?9`VurKo$-quTsdf%Rv|X__u>fmwNOD zK_GeRzEkO)>(N`M=_P)pm-Zjx-_}d}wbl?q2BnwYL9hE|z2+CXms0Y2g*@9Y>){a6 zM?4gieO(@T9h!Z(OtcuS%4@xh!4ZR$XYkKwl z$aE{9`{hXpxKqlaNa>|Le7d|RHF+~ZBfV69N<*G)-y)P>;X$(faxv1nyr(sJmr6d$ zcLf@hZXfLf@~gKw;M3*30C`mZ)UGbm7`-q2v@?X#+?{&>SeLphoYtrp| z0`jgEqWG`!-vko6eMdC=iltsE@81h~w*TIh_7M*SWgmUJN|*Nw&AvI3kK|RMAL{m{ zAn*GmNCqYEli<_keW2Ml54@^=>AeV$XWRD#{6u<)hk}wf)g$ji&AuxnALY9Phi>0~ z$omjD6_mW4Kmba~SukNBv)==+hq`%#{T zyw|~_f~wykPkWiI$)l$Q%Dx!*bo&OOl=P}63d+7s9(i*$c}q2UM}<6l+}HzQYm{+_ zm3^Zgd5bjv(bEcL-vN((Bho(gL_^v4zdZ6*Y4$DCGgXI@}BasZyNaY`lyDy zF!-oGX!=Rn_pcuN_97ERavnr>{l4$9Z?|Tjz8|>&#_9Gw40$mUB!lu_9+-6d_Cj6= zJY*kDiz)lYkOr&WKgOkf#6v;(@1K#@5slSg}!mAq9jK({X+^3=HqY=WQ1&hM$Q#$}TP^v>zM(9)|DJ_Bzxv%F_-wtyQtw()ilFrNflv3# zhnn8&B_HYioba=)>oDZevkn!MUvBgGIf%K?Fqp_MbvTq?nuI*tz87$DNP38eg0ipP zBd;3rh>zsmDESDM`#f#?UV%JhwS!838iHZAt@p6h+aNiW-kXuo{ZgmtrD=ZRBfV3E zJX`Nb2E75nXX`y8^~y&9c6rZw&V%bUz4Vws>3!Lw_w5XNpY!NVO1&E)ivr1`@C*`q zc{gc#X-_ioQF$K{^6c`yn?dg$!DpBE1F82@kU@duQP_=yuD4awi^mqWUhn%h#v!j1 zzEVNS`=ZBx9gwHa`er@ZU1TSDf_NzWBNAZk5fJX(!FP)S5G%fyq@NWj2EIp?bAeRlc+um( zM^TPp2%+(+L-J8M*28gHcJ?7|aOnF?r0-hEhbF|9E*D==QaeKJ{h&aL&oPN#_1)-- z^5vB)E^t3+KixQK`$0EAyV?(GJmBogT9Gv5uB<71jrU`ng$HOiL}{|>1lFlWP3*E# zyC7cXyV$Z)gV9;l=5ZFeFUAhuXFYZN>~&M#HXbo5jfad!o;vm5(s8*@Dnwrk3I&qR zo<_0HN$qUp{V$+@o1A8Kj;)}rf^l*3TuIa5~MlgRYnEyIfh)%08P(JgF zah%rgzC3|l(f0b&aVpn%C-GP(3q2S$P7U5f-i?*y(M}YG-3!K=gN4|oSC8Gd zVsBn9_U5TwZOSgc{Wm7xU-kg@-wa~k-J~O8#eRdf&&g{X4iIL?^ZS6yTuk?J2H6b6Om6GBRcIgJ2CQC9j{r3t-qVN zrRO5}YxOw0`Nv4-jC|g>^ayrnH0K^H9A}LekLF?LWYJNii>8i(J5(}0*a*%LrQgiT zIzln+m?a$TMGK6Eu|F*qV#yG8AmBkR-)#mi>;nrja4{CTm+$U6{!6OC|J*v<$LnyI z>X3J z#h$D2z0mjXtNR0|?zt;( zBdI7yR&4{{XZ5X4wC>(-CDeW^+Gm9?*dL(Xlwph`V#gfqvmz_ISG8#xuxvLWU<+B>!iala|lkd>UPUU7lG;_*m-qzj& z*Kch;aQ$6IS>foePJHh#KavWWyAo5A=$HA=CvUv#Ez4MfeUB;Z2ur?2dvJP*@>cA@ ziPG4tc4J8{_C8Ebl#HM475i08)4)!A)0`EbVg=_1j!!qU$Bup$yGh#iT8$I)V|*{k z6@MOn8hd}{kL6@%jYcL4Vnwv~Cz73fGQ2zrI9x=UBDd0RpLsvCf@QJMSzWWb@@cnE z8}_uEDyewwNGNd&s&`LE!yvMMb6kCIIx!Cm+{C^@Z^Bq61 z=GXuG%ssy*kHD%epPP*xKRM^z@w3$4@v|lH{yjPOS$BGN{Co~|$%@f}jVX~v+VN9C z?*+)0JAS@OJAQikj-Q-MM%WeD@pJWyV#m*pr6a}_*zuFY;qk$oWuuRsitPA7Wa()A z_+VguQb48H*Ec7X?8AE}%|Yd&a|`A9agN{==b%^lZu%jcON=k+eDrP*E)nmHP!c8Y z@8Ng+W|J>u*o#=(OOUqLgXXm8d5sEmgWY-9=FeSC__qz>AvJY3TM)*<39^M${u)2MVWI)(k%MW5oK zPh&rH(WiOn7qh=`(do&V6KL-QJ%e!qJ%Muq?Vb3Bi;f9FEzsVHhg|exjY{^ix-vEZj^}RS~FTu-d@&a%njwOJJPGeXR_7=!@TJuQ~+DmW) z@Ijm$C0045>sN%WzV?aE7-%5U(m}Ktu=7?7xQ^U2QKGpe+d@) zma$i)Jv3ewnO8G(~G(mVwImu=KC6Kg#IcgCvi} zsv@(N{WD^MX{;(T*Ro$pdI^W?SO{@mIerlIwfY=}ZPy@?x11o*G1-LW$}I0H;V(O1 zo>>2qw*vJ|bi@>BZN4jifs?-ybUQy41VMc-jJ^-XVQMr8WpY5*zyGD|aLGX-6`t!= zGR;Jx>3nXlMF+f! zVEB5Cq}Ndlf5s%-N-_MoQ^I#p3_m^~;fE=P|DKlcvlPRBuS(=rJ)PmavNEh$_L!{%XW%}s7P0s><637p zMrm+!ew0(y(7_E z-Myo0U3Y7OrLBVAoY?u%7D8*@bT4zx(EZ#@8BNv(8Q(?GQ0vE%QJ!*Z##Pp?a-4U) zwMV`0vS}Y4EK}CLA*FpiO8ah<_QfdeTT$Bgq0~2_NSOT0lizyif9Hpp7T}r^mo0YK ziSzz%ajl^OPNh6hOot*Z7ijwzmn%G|=b}2_UYpB#KKT{k^yjR{aQlc$8ved>vWMgm zOwU}Q*M5FKEb+=_rMCrmU0za?N4L>RUMUiKISzv+FBOr(bp!v!HLu{a^(KKQd(>UD z(mM+YUGKY^Ug9S{ieH7ny54tz>%pOd())tov-RGBOq3s&cRVP)&w@|ao6_`72B*?n zgS4(U27s;;RZx1XfY9YlX!7XJU&*7pbcnF+O93GJ)a-z=&$~{R78n!XdK^=6D0y_P zhkv_WO#rwNunNjPx;E79%Y{5#!g6^q)t1*TyNVAW8q00M=$G+L9N3u`NjwpEtJo3sl`#z@0>yY<^s=v*J zykXE)Q2w*Pr~7Y(CXeb=+4o5y&-ULhqLV_N~$UM>9XlzIQzKRf9nOQ?oJwq9DNMEU0u69UPj z@DJeA^;(+Vd7u*?<@<9X&#sTXAShiR+v)Fk^gaMS%CBb0l-|cYdV4gzrQlb3@Avqb z_8s`?-R<%7qf)P`6Qy_1c(ffqdt7i3--ZdV*gPLC43ftu^ z@#x*3K`*^G0qwx9->0SCa>$~f^iKEa-J|KPkbG1>S3#KGu3mruzy4MUCcV8p0C{RW zrI|?5OY-uCJlnqM=vRbSvz5v|nj_HV?bGbLQj_;X(SPmsHybd`XQ`mt#Ph)G@}AJ_ zqnS`;--AM)ZQmV$$v!n(s_grcN8YoVeJeG2anE?Q8~JuA;}9$RKI0j$h9M7ABK&-$ zuY;D~6|(K4eH>(;nypp#E%nGdrrGyN@T>CDI#j)W3z3iJ_f$~wZUCR|zoh0reI2xS z-SRPHBKy>Av6AOqx17@Ks{+5W?|vk7`;w5S`Yze1{72&$_-wz>`fJh~B_;%=cMu7^ z921(}YRO0WAlILH!StmN=Bu3okuUjMFHud>zCCyh>zeT4!yi< zAdlutRZx2W1_-^pmejjeGAg}q0@ll$tLeQSG^O`lBy_z!kXIsQQKa<#Oz_!$epu?Q zle|jrTS(}73pKs#z)O5o-sfrtI zq5#B-@B5-0Hf0qqaz9W+U{yJu@|0r+$`Jz})mx+FqjFTBUn?I0WTm)(r7@aBs(mUn z9xlB~tYYL#8S!)8b&t!hzTkC_d*+d5mL=|`O4%T^<6Y`itTaACtByi2Yc0Oi!04UO zSvX7_xx?Zeop?JbhXcUTcP1-T1NV8Yo%WDiCFE`_@@6a2j^KldapN%8u@S#`U zo08;Uc!iV>ME+dRb1A=sgMfp8uej{~ zpR~2lie7^?LB`5y(U;;_p;sJh-aUaOl6c!XL!dUGuT}V6PVYZJE6B*V#a&J<6}PEc z!rL#aj2H{?5;9u(DM~|S6l=mlm`k5AN;OJrQB{qKdMa|&lc=REticVjKr*%!tJ(^w z*7m=sS_7>r3o!-^#Hac3TL;jlu|9UnXu*O4yt&m#Xf(3z*DGN@G9!ktenr)XP4>eCunk_}iNK0XIS4%U zQ-9!Zz#VGdOqPVoJeK5eOBB~jiMpgp8*R0A`laTuoikrmEYnG!p4;oca!xi(;o;!J#CT;S*C$yj%I}#xnL5 z_Vuqsa*o|#eLd&&5f;i#LRztbUse&>imx5O4r9L~S4rG`kgsW?(wq#-k&Eh_)}x1# zBNJ@+&yE`f^xdDgu_ArSvCC7*&4nX)^KsV?j|Zks8&#GwbD36(#dew%U6C|G>`Xyw z2EMp7A8c{h_fSYm}Wjw0*J_#k+bZ z$8NHQC-zP&ve>EN?ZXp$iZS9!A31B-VQI*?#weR{?6sUAzE<-U3vWXXd?j{YPVgv) z##!_$v9&pyWLe=8lO4xhM<|o$#rWg(5v@8Kv|c(n7(aA!xOrOj@JYN^zS`weZin(I z*13)i#rD5H6q|8SA3K%3g73jIj~!>$fipwL+4}~*__Nz!`HoCp4`E}Kv8d-5)dpLT zfAH;z{P5coh2h6@I!5x}H)g**vA-(+)Ui9KW0%0gF@k0u{6+5iSnHJOv7b$_FkA4- z$#C!pC{I@fQ&WS}kWX{}&d8&SFdi8pwo-Ll$V_N3>M$wx{*N+vI-0FrSkGSFH zw`}-@;#u2O-WNn(HynAy4L85Fomu$@*>T(@9xp^)gi7-4Rx_ye305TfM0$NIKNprT z`jSw|;4Lf_(Au!_bMP3m7*@T?`Zjq_E568@8J#A3nqA+#{<6UzX)hTwjH)>G4rhdN z>IK(Y^+WX4F{`$HWFq*$J=VxXKE7j9xNl@)#^CWBW0cLSP5vfl>WESNe9llT`^e6m z*+*97gpLG{FGu?i9xr8vMQ2(zZz5~f(U67yy8ZdAp;*?DomqKDR%8_%d2Aa?zO$8h z@~9st#(tS~ifsr|&))D0qz7vz0@Fp#isu77XCUXuia_p>caXDq8|4fpk*CJM@8Ff? z_%g?(_yR(3BxKc$vw_0mm+;+*T;Ot97I5*7+>%51=Ea`X`*X4(ci0-tF-M9!2-B0D zb99!ScQ8>{Y{d6x=K?44zJt7GoH$e2l$W(r-p6>}{ej%0Gm)2c6n7SuM7WL=$4bqe zxe{9*3?JP*wzlV*quKOThq1y?X>{}0p6y2M8oXiLG@i=3<)Bf!d2CJ36kuvn!K@x& zrqq^a6(60E>S33U6s};CvPv(;85*r2ds6Dv_AoqR)FD0Zo9u+nrp|1}; zmk&M%UY(u-tjl`WBTJ{z{ct8db3vo~R23SKh!g}}x=5B@p2s~5MIumff$v_NZWEf-xA20mI-dxMMap7fwKwe+2K zCt%V+3jx&RG#6d3S(1MdJL6J`$qg;g`^x{xMc1EfQvR9jbr*f6mYe9a*)uLW7IA4I zz&_5t>7svJqf-77c9+Zk5)XYIYj)Aa1c+h^;O)CLE_$gV@i>4toRqrgG}G^d09FuA zcF}1@-U;-+^KqB`G;{8R0N%#&4=y^*Tst9vH)g!*qOWv_NCmKR@6TQIRqShki)^k{ z>~`4acx9DMp#-hj-Q=?WI(8jkrxjesN&tuKTxyn9AZSf*mMeeM=A;Cz>HU?cF}2O&hEjk@TThrW$H@1k$> z(7V{TUGy%t7w~s69*WS#I${5l8muT32iSJj;40sCoeX+ETjrwod+0mZB`*375B(3> zeCQ_ibWK2Ow&{EH1k*J@2^OKYX6x`p_WRid{Sr3p;?H5HUGPkHH-=nCUJ3gb7d)Fi z=Yl`Z?sMgz!cOBP;N&l4ue;!RY@>_6loh+^3)#IWhm(H^+W>tkP(SD?@vs{Eu_EiP5uog6Z5|WNu_vO8=E|_*3lbGJlA} zo7h5^zRj#j%A<38k=e|$Wq!e*U`HkYe4gK8-*V;O#$HE0(og5~BD0H)OMQZWJG)cT z;TF*QnfjhNox6+79enIuieZ4xWJ_-rYq6KYIYeKI?q7nq9CVUb4tg2Ipwq~|^j7iS z^QE5_?`JOu|20Gh{#v4=(jpXphGAp`9(*+7Ed4BFU|~x!JRr%+!PiVN_&Nw5WBh@| z(m2*I6Aa=`qJ#Mkiji-S;uzj5LNWOEPz=7WAzs=d-Wy(yct7C0R?NA}_$?Vzdmuao zzqR!opUcUtOkQTtnt6^dkTEq_gpaZ|p7UQW)@$UoiT4&R-GaIRp&T)%heUmleRF}Z z?JVJB*V=cm@_Hjasvq(*m7mTmRQ^VSA(#A4^2y&+zue!5w-SuX=ps7e+XzN|e2!qm zy9h?Te1TxZ_Y;hIe28Ggj}VM{|0cnRze_NbeUD(oPZ12I-zOOH4+%#79U>Uv}CG&SsoG14pfPM$T`J%lO|6YO%M7t;WQG(GfpP(4J@gWOf#T_SrY+&u zDZYfUV-kLwVi^Cfgg>BomVA#siKIDew1R=@6!@~mSWWND-u3T@p6<$!f#WI zdVg2KA5gr43W0y<5B|UGy$yVn)tNVZ?t3Q55Mr3br~#wilLVMVDhZ&1+U7x?#hZyQK+Q>^O$z z?;e*Za``@QOeW}f7vDQD<6K@(C>_Mz_3RHQvNM?=MJ~QCcr(sP9QI&@<*RNu(be}V z)7ZVPU4K7Dn(XrnsjhD98b4tvjC1F`B3k6E2a{az9wQw{?23&my4FD$GV6Lym=Z^3 zuIR=N_Y(qsGP8Eol_v&iTb1e9(Dj+jhE5>q|}=MPaPZ!XbhPvj&TfNDQ;fcV?f%4-I}_w zyZc?hx12P*E!L^t_3M^zyzGX;^8hDepOYqlFI{zAr~atG__12vWh_^CX7PH3?o}IB zofI3~Xsz!pTFbkNw&(`XTXn+?nQK=$964d7Ty%phe_8j(e(!))2UQdu)&>ViKhAR^ zPRBbt-SnI=A+j-X67D9FuVjKX~`t2AhUsO!})dD}4U}KMy{PmkCFFP=C1ixW^VK z+2ZnF1QQtdlIG65#Ll^9lM$zS4Z#vz@8eP&?`LKL+<(SyPMN82=-ADIDhc2cY z(kQyTCqt*ZLZgdqf-YU|<<;}MZ;brj?4!%EI@7PT^@{Fid~{c8bTQ>|>E;nZr<)st z?yqb(m(Ra+=wiAgjiUPoKJ@%{YILhKx}S!C>U8DY!ofvL@tJo(0?wtIcj&6s1x0r$ z;B>m(8r>R=?sOmBQQ%Xwbh>Bx=>FcJi|L*;itc0|-3=ODRu#gre0WDZP`L6e=T2}d zqtfszU-^a*!1$9LKt=ZrU-{mm(Z!V0rTZo-piWoL)f7?Kitf*CIG4{g4qY@e(kQyG z0#4`iW{vJyfK>T?+()+#_!KQ7RNvq9(X|}9=SZqHK7M}PNB16$u7z+#_f{X>=ooZw z^wFK+(5)vi7?t1aeRS{F=r%ZTET8Wqg3jkTW6}p6k$^N}@1|?o;^C`TVd( zcbWr7x=Vd>6&r(Y$|qNxdoz9%KN>|h;ghRJG`dX=9OIp7=fjof#beN|vfVH;?BBSeN4muKJbrrm9&pm9R{d1^`T?h>Z=aUF*$7kk z*q-R=+X44Vge#-)vEu3YUIRY1;p~6)voQYxWP193@1#$yIx2j>0FaLFH(L5G1WuK{ zZ{S-`Ul8>QC|#qzziPv|@)80Z`8CghRCFJNTc>+iqf6DKqWd5|bh=^SyV=1-OX2&X z4d>Fm$Ds>#mNW|P3;59K{$8W|Q3oH>yT-=n)(_sVlebZM@U8aY3!nI0 zU2NlX)2Ghb5r&3vG#C2t9R@zeC%!m-3g1`36rC?TYxfqyl~LvKB^%DAy8-P3@g*HV zMfZz<^YBHZ+Xh%g_bPnrba^I!aJK(S?fCrMnmL_57ychDf^xXr%eB4d>=}qeEAv zQPKSl{Pq0K(C97$CY9et4A6DDeTesnLyMN8JH>``=`tSqe1!w6=$;OLo$efsE@es4 zJq_PF-5H2Sekh~pa%>JbmoDdDr27d6P|=0AhwddBT`VcNbZ4Ue>vZ`xeAK~3OVOQb z!?|?7<*64NtR?&UfM|T78 zH9ELxDY}2|qx*nEcdY}f=-%t2yFsJd4Om6@`(U!p=N-Vu^?PL$KI#kb=kobsRA`p( zbq=6{;~E%Hh?wJli$-@n{1n~a`s&dmz*mgVzqH|8x-U9(uXpe(x;enc9yASvj4x&_i=9_|geh)ZwH~8qT@#Xg(jV{N+D!NMx9Y_G#b+kutZ>yLKxtc2Yp!0j<#(?~`%}S#nJtUo1;yR1RqKhbk_OK2M~Fk|k!Fa4MgKD<a2zY@vN;I1<%H9p=_9V0t*z%5mCadW$mRvJY>~Cb zm(5F9_}cm6Hl*(IBNfYD!WqYM-n1Q<5=$Q{uTSLr(y{!1_Jo|1G|WTzNkFayWW{Tv zqUHHR=6Uz#%Ywlf(f(i~PK^bY0BU9e=juFXC!&)) zaD5tF|Dh#c>_4>ri#j|{!ZOp$19GsGFu;p*I>CD5a4s`&@aXcYq>-k-=>N|*6>R)$ zoF4pj)q4AO@yic}O{Qj9`tlgT`<;T$8R% z7tT%zKkw?t;@v6xEMgogvYZJ$dF8<{Piix0mP|33b2jxV@5 zK0H4z@V_)3A1;f;hhxIb2@5gBi=!ct-_4XdvipIw?+by=Y2Uf8>s`0+X9vb=;n}Vn zg9)OQF>a}>;JSt0bz5-P;HM1RuVUvmI2O_4P4l_ghUwvrKKBfto9WW&a*S{?bp3e! z>GFqjZmp-wpH8;Fdbl6H8sT;LDf2(@;koNw1!(pUw8p;JxsnDZ!Zmsi$Nr>L)Ox~I zuVzOGU=&N;ZNYFz?q_wb-OLS^SeH9EvK<@SMqyJ>fdH8UGwH;0ZrRi_P$Qah4~)^}g__qS_Na)fXNW zWuEY;FZ^8bdk_6{ec|Vc5l^_%c-vqBF-!c)6F$oq|9tT?Px$%1@VR2p6F%1$ezEvp zp74u(;c<6gxrGq!(?1P1%bRt*8XG$Q9`WgBU8*)Gxclx|$E&e{^I6yoC!4CxN#cCS zH{Gn$)!2~9wNtuTr+GIzn=rarr>n666C|bE#($3Zh~sXQ;q~GwPxw^9wFAbt!=s|a zakFk#o9Bwt9eQ?p&J#B~Zh+z3!7TBV2mX9@$K6RA3+FwKdjoCcr_XV3rj2}Ucii{W zM*emqP|+B7x0k;(7WA&au?Kt7 zPRur~RK|_qCS~!*uULO$Z^tS-Lt_$f;bp$Z1d|CzI`nN|C$qzgEL9gdkF^VoFwOhPL(VV+!QTY68f=bt&1T10rV?1_Qdiqwvt?Mlm-4Ywl)vZ1O zH{+{(DZ0cp0lyf2G}MU`j&#fLQ*^%p=IM0VZ*WYYjH3Hh8_uQ6{)6~PgGSMP5O6x( z#Ts4i3sZFcdsKdjFph1MQFQ%#RM-!ZuG96qbp3l&R%moNEKqd6gKs^*HE^i3leVJ! z7{2vFYF(gK4%Ex;=ap=uT#UvVT!`X{$Ed@1xF+Nlu>D24G*1e zn?qO41Qc95;PiZ`H4n-`4StI5Ok`ZA%l?{U7-bY+oHZ>sztqh$ziNh|=tdAhr^~ew z!jUeAUyANah_BP_gCmS^WfWbW&%vKdcRL)!r)DmS?g0FCy0>U_p{91}a)<{|x86Je z$5n7Eqv&$xfFPGH)E<&DI!{{HmFj zqWfF;>vZqY=vo@x>302f^J^hqBf^z|Q<}4EI5)p)k5s)AuINq%oKE+Cjcx;AReqQI z=yH!#vHbGhUOm6vfMb50p|-@wB((YHKCIDY`=RKnbGfQr+yH#V^2_w-bk!cDD2c(S z{4NBXp5I3_x=juo(|Zia@aOV*2jbPjtqh#fyko<;eCGU!@zqRL(H#MtPWM|HUDi*P z->{GF0PrasB&g`J{nYV2q2Z&fD}4WoZ-Bb#+v}uH&7>9X*8!*Fdsf58UR>eZ;7i|& zz^Bp#F!!5lb2?p~TO(i83|-M(4IrKFUXAW-jqYQJ4^X!}4!~WkJRY^--2CPpx@zXH z=sp5}o$iYo-3v6jT+7wzj>65kt}<{+v)P7o=~h6#nP0X~G>UE?;B>nCG`jN~IL5me zM0L8nmzr~GWfa|38_uQMQ z1pd)hW;ft;qr!&Zi6C}|(hyE>pB3BFQNH){a2iIQzR@v(oJ**d57U9AhX%yGcSUl(Fu4)fufjv_NF z$)S_@*9I6ApKJ2?;#gf7o7Hyt@>}&6a}>rWnQ%(Z30F+cEe8&kG&iXa$5wPH zOGsaj3MQOB?pJV&;jhc(Alw#y45xoVE-z4mCgsgtOCM{!^24?Cg67Dt$~o~`dT&SZ z*O^cnCubG_%rBdt)S{}gr_J9Vt86Yo+D=Y3=Q(TRc2oGFY!(VzwI}rX0QPzG-t^%< z56Rri@c*P_b5`qz?It@nP9%KhgO|)w}erXYiU z*(|1?`D2&O%aM>+=EQ+LST;rSc_t zGcfqJxd?BT^v&)6#yfr24!j+{xo>o8%c9lsy3 z&Q6}2oSb~(oxUYi>FU9Xkw=5&`8s1#1F3!Molk72&we5HP_jOq$TnnoI%9G&k`@u8 zeoqH5TYaOAd?{^#$QhAPO5e9HqD%0C*kyw~PsR@7g{Lg?6F_d}1V)0)%?7;HG(Z}` zcltV!qxm(=(fmjLqh$V!yb%NkD#!ukuCyjy0hrR^FPC1@FB;(+M7~mW(?lcuN@~*I zjP=eBj67n_?XMUK1}3LzKWa|GdobUOHQ>#cDx`Pd?TKvzZ=ce(m#K~+)v?`g^~6+) zDYtxUZ!_NiXcR{Dyg{VB@}AMg+{2?&;cmdIQTO1BCjc%HI0J*%dP04#y&YaPJ^R#1 zc+&K|Q8qnYlCLYPJX-d<&!#)l6H~$dQ&Z)sze&H5j>xyvB5C=e9Pl&>Q@({~*Ba8! z<87wKfoJh1)A^Dz(ueoPrb?ftA(U$cQa!LFk5~CdFB#ygL7THBYfHP4lAiDkQpeeb zo>;fY*NIA;=;%p@Qat4l><=RiJhAZNXoUr6@zGtee5I(!i3m#$k7ez)a3K+5Ggl&( zFW0^e`7Hp$lro)s<7BEZqo)mpvO{l&pEvPxRi$aBX&bNupwBZrBF~c&!rBB0F>^ud zg$~0K^_xZ;wKFDt$n(^&*<=kFcxh*DZV>p&vwY!;ILp&~70ZAPoCZq6r0fA}7+f%v zys(9(~9y;@;x6r#TMSQ6WPAf`hDr{yHey+Fmih8X;2IGn-Sxv z_?>(;ue&^ZQR1}0bT>l?HFYp3^RqBL9r?(02)rJK^5cs=Jvrp+yj)-E#=20pz1z&! znS(J=cE-Ms?jo+2cJ26eNbF3Ub|BIn%Fa#vX7H6aO$QfW#-lV5*C{#h=BRn_(sZuF z%vqoTcZA^x4a*m5ZWl1*|IR1LB{Pe%3WG0!U?XZ#?%`NPqPG8Ryqq&-$ZS+Dv*eti zS7Q^(&fI@?K4jDmR^g4tO4J1dxeXiyCoNfn!|}DXxvK14rGb5f2m%6OF=Oq0Pw(7K z|5E8+E@Oi4VTSHmgH88MkRa-W5|r0Ng2j>XeiKBD&N;L z%gRp?BQuN%IU_OwZ$q^hLHwU%82CTeC`UaN^~9>zOW?DNX5u@C`0zbpDA-gc@dZK? zE5kxW_Ow?5Bc*1c@Fl%O6y+ZZu73d*5I8bca&}^+Z^)jMR*i2msW=FHSRFC1aP^D+G9i%z4-ax z_|e06Al!cjrUHJ-wBdvMy_De?R-Wy-(-fBSg#99ZZIyNR8h4pn19t}RDA`iFxhzp> z)oL&g;d`w2ZpdMsE_Ix`n`>CQo9mW-la~c<`xZN^^AGw!!87{dSg2HRk4C|$RWsX% zXLTO*gmYIw!SJjO_ihx7o?7CcByRVFtDSy!i~x3dZ1jZdyFM8IG_lST?i@;R2=Z)B z))PLtkQ99JY)*$KyiR-??t(1TiEqMfxv>f%^pbDHc;cTUzT}C2j=WpC-i@zzoY@{c z+w*x(`~swnf2!#9gril}4Bv?P0^BU(=kVj%m#pKa{PXO~M;$k1o@ZY!13tp>Fc&%W?}Glo;9t8rO*GaPikDBY)t1Rah++azAck6x5xo{jk$9CTB5c{ZlkaZ`4y zap*zcqgZX$`_A6j`5W)7ihD){;?x4X<hoVVY5# ztc$!eoh54`@0U347;RLjs~q=A+7SPZj{6qcA?L1l#DAD>Y|16yiSJvqk-h=Py_Yu9 z^-IV77Hy^v{2_dhHqyx@Bf7bl7Dtcpe5CDeq>Xg9IPN*L>k!{L!#>7IiMGq)_TA%S z?ujRabLF^u4*mql^b5g@oTeZ)``&N=`u_=V;)ubCZ|;^@moHnGxvmpe3!E@3OV@XI zr`Gqb=*?Vr!)gWVo(mx&Kg4^vXqtH5#qG-kKk3_-2@H;majUNPutev&Oc9ODSSKZj zSzcCs&7u`2WTKP@0^w>}c|t*6nk%o!wJ*e#x8TZu+HJS3_HDQF+Ff~{t$nHOdq0m5 zM12fE#Fg1P5%<8tPZ?AJX=w9@>M6}w`;E3B)DQQZ6Ni>U{W%-X-Oo1)H>$du7Bmae zd=~%Nu+W6e~JAse=fHI0M)2q{ML;&fk-dxdba{OYjX|ft!e7bZOAU^Q9bZ5Z518!v$ z-H+OEZhpCsm2}Z;N~7q`gTJ2N9*yoPfK>Tq@2}I{hj?u^D)}EyX&^?P{MJIqNLP(M z6kYOCr@K+3%cfh=tp{SAt_6JTKb28*Yi&3;zuebJx=!~b@i9&f;B>lu8eN`AP;}WR z=ydyl??obTjLL@vARXUU;A8q(?&O)mM>z+mo4&;eVEWXkO5r;UKONr#TKdk=@cqoj z=gPqfAmBJb8O0awPu1!24q?(&qcuhMAK|Cd-J#KCmrgjw`wEcZ&!x-B`a-ysQTXn& z;oSVjO6>UTR%sO6Ho)n0AJypU=MlPnbQc2OQX7>AU%QX)0}fp^I#hH&?W4O>qiZ?o zV}4)o(cJ-js?8u_#pmz&=sxPuttSwSqWfJR-KR9V4GtXXeg{8*y0mzAw!#5#moCRb zfOGl$ghO{KfnZdeNAa!mc|fB(&4DA`kK;$WE%?zq3w-nKPx+r={9TTJw3RV*rodB$ zJ%DdiogN*IZLu;6?q7WPRstW-<|?D|;lIQ51>|D@K&)@);zu~n0C6}KSw&@ z9%+pAXLS}C?Yp8j?nep`e%aK=DXJ->&7W#6#~M#_d_*|a4im0eJ8U^{u%zL>eBCIz zZ0q!Pm~h3?cRBp^c5@JJ3qRtazuRuk8Dp;>Rn8YW!DV9^qElqRD69S9XnXD05QrwIogokmQ4+t!M`uNs(%{n1)~kI zNm<4(%MV=p|Bei-uNeyE>w-&;gcf$T{p858jTO^ZjE2%>!+oM``afpxjD0Uzf>pJa zWExXu_atZVr5x%0`e z%w?#aISZxD;ia=yj@HMJ=fG>RAl6|Q58qa@IL+12by?i%_lMJlD<{?Un{yVYHyh?Y zVQo!M0|#ykJ_0-y^X)kIq=BvE%F%kOT0;MI-QD2gK>K6JXXOyqtxV)I+0K04@bXm^ z4GqX8*9=9a$O-EOnd+S}eQjpvllE%z#|BNN_i{6TPK9x_;!r38N|na&^43p}Mq-x_ zZz_2>c{#qivkxb`(|b2QQZ{ve<*zrPe14WZEB1AkNE>1VSByrMo*Qc$jkG`=oF7Q< zM9RWL6%Hlmt+4U7ulUJ1t-)5FgEy3zs!?0;4mI|yf?$p*8MN@UZVUf=T9*bxt z{0xs@-;+i*R3AH7bGZS|n#0RlnQm~k0_nCYa9iT3iBNyvZlt{>mJRRP{Z?O0EU;HI zS)WDLYCxG7f#E?5SdxexFzN@cx;qw*z2I=lhBN93$F)+c-n5|;fHpTR)%hv1$HRq- z!TmS9+fL0*$+jGRD=KU6HMW{}2JQ%MDcOv>)fnKIZ^K^BHLyGFH84HwUWARc?nM0y zf6DN?Mmb>5#ZRqw>2MbObvM-5$GPF<$ z6wip$JF>1H`qV}YX23Af#o zdFQ$e(?jgquF{1_IaI%Ive0^-Y5tF7$txaQHqM^;-cw^gN6@kmaPZ@>!HFyA@ zt8?ReB6UtGEvQ1$9Ke6JiZSVeo*oGxTmycD;g9Yr#MjfuJL}lSD5L0>*>Eo17vW}n zl`lm%0DqnCqZ(b#D-~Vp*YM}Y-v zSL0i!+YNkdBb8BfSHc5uE?w?dAYBEk=(3&C={}{=)z>i8U5^Nsrf&?oJ-+rjCh zzt#a%bXga4x(776lM$xq`rn&q1ioT)p9N8!F7N6gT{Qwwbe{r{PB*8~t<&hTP65=_ z)hq_SV!E1z4je3L?gN}|h=Yc*gP?BHFf%NMDZ%CR{Pyf*(w1{ll_~D-ErG`9>Y>CzQ7$a(NH6~(mQa6+UAc=& zO83JS*5SVNk6@eDQ`kv-*Jzz+9DH;Hnx^Q5FaLD3M#K*HSwDjP?}x&D_-*R_PAnq& zSBwVFHReq$O~D==>N^zPN}8ni)QCB$Bz5-Cdc+IoB!;{ph+$5eFuW80vuQhJ>k$Ho za45#`U{2vEktr84FVPe5_FqcL%?rs7`s$Q}L_FJYJQ%F&vY>%dRgiyIH) zlmKkA(Tv_ZS{Iu*6twPzF6^bzim<(NJ=Vir?3KAdBm85I|I+#S*p2XC`ob<_t`W5k zNLcWYunzBU2k#q1|MJn`pBfj}mBwM)yq}P>G28p#%klQW`Y(Pwjh7*$28evy`6Rd& z5*)GCl zyNs4>Cfn5{U1#U$7rohxni8{(Gw8!PF(<5--o#rIh)EhY9y_MkwR1PppO5vVk?Uwr zA>X<#N&ik93<+>U?8)xJOCNjtsTYeKY^d6M@Y-cYdf}13t9tRszvF8lJ21%`uLinR z(}2!3FA~Di--SpVtdKZ2WfzH+(5&?=NF2F1GH_(FVWd+>Zq4jH@~OCi^o@nD?>KxK zt#;Opa+X6sic_#mQG!yQV_6%cYTp>H%yEAI4fSM}$_(to__Y<;FV69iGM)JF?D!D@%3*6N%Ko>z*J1f z_65D;WiO|h0B*SL^LVjmEtr6qD0r`I!Ekp~!BB_B`|t`z%}{I~zQ3^66VBN|!31y{ z>S|9oNAU&2J>D5lI7izB!#&hz(vrj)qe9{wsP9ZYBxJR4!ZWc^^;S*m0+^V_7 z6F$`!-Xw1Jgg5!ZTU{L;<&-+S&p72}!Chs3MEnjm>m+5g+AI?mY-Pgu7}hE*-5&)# zdQoPp&57chu<53pa*y{E;HR5p>T%Ki5|8_I@w`JH!E&6R1u)?$tK8%Lq~oS6a*sFn zM=_kT%01o(JmK|%XABrlS*^xJ_8qY4rmR-uLi-@>nJ5;H?^|FKPdPSLQTIrj`JnyJ zj{Qs8&ZLRDMh5Xqw5bxwd2q9(LV;8_*c`e7lL!o z@&EvE;W{tYhOB{EMHh@<;?lf)WZ=>VBg*MW4zvF&@Hq!Tq<9?Jj()onreu_4jyVr5Q zKpO(K&v7514d(sQalb_ynKDbHHks+j zuDW4NEu{_V-9PSb_AVA!WXrk@Hs(_T#e;o#Y@knOx;9|%`QpqC8%@Vz~0U?)4pO$6@1=1opI_1l;12LM5Tz%ielB z&n^Sy$$%v0m+hHxb1?t9&Lyken1x84nGKoqdQ#n)8?xi`U~%Tg>pC1bAG5(BC)6pJ z%(biL_hxQzbmO`X+q+MHHAxqlAdjV;_LRH3Ti=%&r|9KAedi^ClhI(m_x<=s(bni) z8TV&y*F4y!)6nLR?JUh4+j9S-iIT>z+a(;^4rLVFTp-hRLxX6;<^pIoek4ygc&T@D zdTzrvO%(Cyuac>PgE2Hqu2Aqy>E*u;uFnt`Y zDSVYSJ~w@7lsD6-Msx~axewn$Eq%H!`)?3ePan_XaSWmioYMRi{_E*m3dd6TF?}2@ zs`TBAZ{Ty&$9I*OJ~g6L>H7@)bbLFs^i^s2YLEaueQDrRX#$x0U2emPWMrbZjA%S^e*zz?H+^f$9!}-j%Iu{0#)Gk zMw+W^I5)qKI&{^@TG3qrI6c2lX>`%uyXE!|KDs-BkNi+Z(fzuQ?p}v3$2l~L?$>;D z2Q<1IJ`s+5y3zV-B70tEVe6=?SLFQ&e-9;7E9`*sX>fnOH;T} z0wFVV)G)q)ct3sH?3vqkXQKY)|AeOP=;uVgm3=#uIrJktJ|03C1JCe8gk1hK;v2?= zAz&yO36g)ft*X-VtF=w=tpLGnmR^PglHqR>Xl;~ zR_XrCTh07`8b%ZJ`!eptp^4e#VbL)$Ju%zh*l^!4F>U7mV4BSnhsv{w!+p!;ttE~P zcYApnH&T4IphpCLa{#}pjYbpo-aQM92GFQDwMR6dY$~ou^JWkHT39kyvt$~obD(%V z^wspo`T|O(0VUIbl4+n1ONODRe)cu!{Nwo;U~9sIZ;Mlnrc*N|xVh%lvT*OIgF&kz zXGE%caYK-CUuJ2B(BOz+LKj{G+*mJ2;tTh{)Npm8h2Ki6$|~fnkA#r^&;y`nG+}k5 zapvnKkT}t}6=nMZboSBgp0W!E_rGo2{99S(RF z6mRQV`D38^L%2e@S0P!tU!8arIAe!J%MW2IT<{AAQxV5EniVr@`;Ep;WoPd{uS>z~ zcpB8oK&xyN+UsMYB{`a&i_#V?b6we-mj#a2d1(=4{Ae~_78|*vZ$EBFQdmUvrlB%O z${w?H_y^Xt*lQ{d_bt8l(4t7`;avNFl-2f!+paxycjOGbWn6k#Tv6L!+ZG>wE^-FS zzw~fl(stiwoRJS9yl*z#$@p-h^^AO&@XCD&!s?$XUDzK^!ngi&>dSnlMEd3XdOzoU ziQbFl*OJ3AP!Y>Z^L-t}TACNDjo}5YpbV-l$+E-g)ua?3zM~bKCH(AljPBit?N>QemE&{n=x; zr>nEi9V$yahh5B*Dkj3`#dD3pzdhGPo&MQlBKJ%~ATu%hTvtQ>Sioq$JyYA?vtVFU z3|yMU8dgX9p_c=J_PeuX4Fg9+fUacwUD!R_e&}ptPexyJ`0sdUOd}gf$26jnw^cUY zYka}HJ8)NUYssCZca&`jZJv;*jOt^Mdcf=Mt9eW^1B*J$+MmK_0nA?e(t!* z|7s{Dcflq+`Okf-2OT$g%{O~7lo2yQh&gY89fe(v$=_c)_ON497f|kG&%bY#@i_)! ze41t=g*nb2gDJw%pW`aRb8Jd_w>kFzTzlFZD86oy6(6ZZt7w= z7b0xTaktS1@uiM?1#P4=?YKK>BT+q$djoAS<$lNg0Bs8Ed)VJP6RZFetmcw74o9@);lD^8vrT7M@OZOf)*j6f|=%(PI<9iB7&>Y!o zW3UyzMtlQ>o4#MdL3(H!q*3X!;L`EEprwz^hQjy15g&hU`hEk)6L2e|()SAdb$rz2 zs`R0GbMbxK#^3a+K zmcoy6z-~g}+k|i6bJG`vkT89!r&Q_tJp6Qg)V&gp_-gP|_}Cxl>1zQ#_GQYb^t}NO zo$i1`SM|V(?mq)gryJAg>N-KcF5?B@o3Du4v}C$|;C!o~Q&dHEJeYPG@*H)mM>_D2 zaJrl-xDEJF--OKqZU;Xcqw>)MAUz)o;Yb69{9|9J`1jXjMtFrtGZW~@78_Ka5ywzBY@i^w1L7M{k9>!AcYA?EI=OyvwH(s}N z{byJ8wypmxUZo%7e32ZPuv@<_)84(x8^t#kk|@R-a$uc#HP%0itX01I(=Xo#D^x#= zPkFasjvtO8k7;Q0XLEY&^}_ZdaOAx*s{XUR0Y0~FUI}*yKb02Mwyc1k-nNV)65&)o zq}rDA;HRgr6YgSk8*Mn3?mci5pURh_Yr#*a%Z5wQWqYjX`rGFF5mu~iz7zgTpE9qi z564zv{MuMtFpl-j_2BY z`$BZjLw;g@y76_a%f{t7of#ZCOD85QQ2b;5n32;36*>9RQpw}l_^(4XnE zWph^X^CagNze{BHg|kn3+`usnj5}_q2X(H2+_p0gZTj9L!rY!HhrX^XfV&VHu!Q*~ zk^gQV?vze08Gd{^wCbJcry0`$*Z++XqoVR?#s8@uo)8lG zFZW%VP2|JD>KUgE;qH0U9A0UfZ7+{nJ4JB*}(9`0K;y_T@5u8 z8gLVT@My*1hGa7ReD)qU^kwmUdddFy!E^wlqQDfq0uWl1z#ZsQ(o?dyo8TrB-^QOC z56wUdm$xk+oiI?EuLw?R_?y^_;XsA>O5kYlaNBT2ATc_j1*6So|aGr3dFKu+m_C#Y{-}di=+VL##X-ykOSR zvO{GfMp?;-S#s;)tN+2=iE{<++Kac0${M!gmIIVelkuhXgD9QElHtedjj!OTbd*J~ zc`k0uH@+n96a6=zZ8QXqntwQZ*a$7-34=J&U@RH_^NO#%^Jh0rYPfoI#t!6oqVd(h z(TOAF!$zRw=)`yaE^*cnVCMt2KqEjZbX%v;91w&hny8{Hu$qEgahL3 zrbWS#jy`XC00|&m1V6&?M>lm`B%{)I01mbd$|!s_@PM~V_cc^-##iwa9IJ{>cZWuo z<8MXx0w5z96`$va*aj)X_Jd}I4d>Fub^=LPwZw`p_u=Yv)m;w};2>T__icRZbVq>? z)!#LW?k{XOmu?V+&HO4@MVERZovym;fpqnKs*^xer&|GhY*Up{bW3bFm#(@CK=mAo zt^qim?o%3{Sq3VjXGDST`24Sa6;xSy5fp?XA>zSZ#4@u|BRh)>r^uLUyv zx$?IG_*9zU?S5x$IG3)vPh0i0iteWXr_(*4@kQUK>Ys!5fo`!m=w(j&m=>D<1vuR> z?KGdj4?#WBfq#U%N;zOFIIiWWZw6aP_zN1G%Ewj!>G{YZAANv};K#kHgd^X-12~;u zZy{hO{P2gCq zL_?af`ZT|+6Rw!7Tku!7iI92}-Ka3ilP>Foqx>tQ;4XuQE}MgJTlg`Y{*+-`Hr2X| zC5@{K{7^RKIycxPjht8c$G;q|Wj1W+?P|Yq15eNShIHPuNtDgvI}H?#@$7{F@XKbg zc8+Dt-yf@NE=Af-N;WTSnQcqu$;zg4b;n7pA-0i0nl7-69Q#1d-=}~!vntcxC5%h( znVfZA%REuivA!2OR6eq9jwn5)?6Q!UV3wCwiYlYptig=&45QYVY)moEH0q3cqtTdV zaI6FI68|;#v1dEp&yCk@NUL8iSHMpho7J{V{xQqtVkG$FBlxn0K@;wBxCJKKm1l@xC%RQ1Cc%H$QthVHPVKBf7D0|%Zj8sK{;%7Y#vRB@NTA<<*Mrf zckW`E?G#!_ot-v2-PnT9_`;6Q{DgNib;a;-zxZwP{Y}8*CY1XDjhjw}%;|GeQa5_1 zG5xI6>8Y(L;F0_HH>Io;au+x1CpY}#sMs#|^he(uib!sS@joG$g4OM-wxm1K+qiRJ z5p@4A96VOF^PRq1e{e)3%3rav>ks`^G?|?egSOfPFVe@XQ*!BT4buObEMCxUy(spB z#}*EkEx0IImApD_ZAot{|0@xlKL~8|#k8N`Kh7(Z4;(ypI?gAg=A|x`rFP(%^qNRE zJZhYKcYC@$z0H`L-eTduwI#DH^0)}r4_T=`ykL28N~J#hOnMtrHUX)6WHh=Xo^6W7 zheJjyQZ*52ie#-Vmu3eZYmO}(7O`+LmKQw>)9Gy@`aEzcx}jah^v*Y}tQFalNn|g_ zK4he@V@ga+Po!Cz;7bpAxcp634&XiBKHZcO+0#*%JDMH9Z6IDP2n zqgLNJsg-r2zfIolbE|x*^r^(e1Ke@HsjF3k{`8{USsu#>wDLUb1-fM+cd z;x3jcZuf!C|8_;2cL@bSxv#6Q?9_dy;l89Lbyli1)hu~9@bpYcGqo#r=FUXP0ZYRD zcE7;sgmgD)q&qEH-mEVPK^Y^3d_h*9B+g(;#w?w@uYh~&)0CLgCFXyBb!==syK%0; z#rMIM|**!ft!C@{E<$Y2~>T`PkHTSLrGH3g!B1U%8%^+tjtFEU-VaZNe^=s=tmT(oUPj zS^}xH<;gC6o4zftY@@Ac+0dlayj`cKns?c)6;97gU5K}SMNhgjnKP`j*j5RqCW04w z(T?JOA}k`A&THFOZ>i5_I+pRw(_s-?nzm9nF;ahSO8n2zbQvRS?OMn)7uex+R_-U6 zT-JM%BKqs0pJdn)_O;sa8GB%tm5pcZw%(W;#Th5O+?;Ak&62fBME`y0__m4d z$ZtSFK}E7LHwEeLVDzU$t^|v@waL$p6xQ zx1AY}ck>+H&GGQA{(bST61=myW2bj~?nJWLXBMu>$ojzAV7J`Ib4Ns992%b+Kk;$n z2XCrU-P#o^>)(Gor6*l}?ZlhcalGnnO`14_SG;roJX$+&&2Yuy;J)pnG5OkeK)&{! z#x3(p@)5lH9UoYd55rEt7I^);Z6MJu>ahmgo80nTJ61d8d9p-DVjEhRl4H&26VV@v z>WBK1+su)^-eV1cE&n_kjG<4A{OmFIY#1BFXT++KktFU|3-^KUKcm%;fR zsY~%pV7AZrC~7myrzvM;!|1&--Eq7yo#{laE^F%-kxlKJx_($TWoT1Z93!AjnbQEr zmTM~BvR18ENv`!kS+-0R=5&93KMT%$J zw~+^rp*NoV%CY+TEr~2RmIOzVQ({$Z@q8afQnwl{NI^V%mod2S^)*%R^nL6vhgj?S z;*GiXZS`CJWzDJZt3=ra2UP5r9}8fmJw9y4C$||R;`&LseWNq*Mtd+vh?mK8jK|D4 zUSt4Ng)td@|JStk@7>8n{d<#%#Cwy8!#T6)^Pjb&5!%`N-X zzNgAMAPpkAYOo+jstvG5Z&zR>w(xOVLet&rAqkZUo@h;XriL=zwgkrklSUhSe7~w% zlfGw!g*^4#kvMnIjx#-XKe!T&hWfuVB5ti4gewdx^-WFBWhM{V9Jn`8Gw7`iIkz_a z>`fa_Am^2Ew*5$DPif-F&=1}EI#$`#f8b^F`{T+6W2m@2&#|JRp;JUp}A@UA#5NdDl*ph4CJ36ONj_}Jkeunf;5597&pEm+Oo<*W z&2eEEWs8)gjcJd)X@{`wNQg|gF%2yNS}3OTkvD-;-UXQMSjg7G2|k#?U|%%kHfnm`+_fsJWtsln6htT>Bsh0=VRt2 zXnQ$piy4T$EuIz4mkt)%z9p|bl|NN!2K@0Jy8m+LcYpTpKzq$rTUSytHOU!c7c z|0@pHKZw03>H5rkykG*GY4ghK<*vLg$|Xum_VuARDAbwlPuuP3#ZG%#>a?fv^sL-g zBjEH8Ga%u1TRlDZ#AtJl>9gC~ntryX==*MwJWbdhuDuLhAZR@FSG4yzpgYg zTTsI+BU|5G)6X`Wqb1IIS(agUydQpY^P2i>nD=tV!kBCAK#!GK6P;zWWiT>07QMf} zW81NY9cvr5P;y>CFA|RIek&Yj0@yNn~eWH@q#dn2VC_U`JJe;y)ERKFIC zRln9go?H9YF65vBKi=0WYn7PR*veWqe$9IF1U2g$@3Lln@dK_|l#5kbA558uWJ8b% z5eqpo(Y~g!)og3mWFmKBnczswDQR0Ku-na%iO_qL38g)JG}K95J?c$hK2{Ki6JQNtJi4T_^*w_C_~KJ2uQ18>?P@E>5S+Gn?_15dme$u5+Vfc z%H-_`iNk$~a*y2GvOPFDqtEWyIof1j!M^?URPo-u1U>uJPAhX|?)1a4C6$9ML7b$I zRqlU%ZD!X5yn_{%{e!LbD09Z2AIr7u+OgK!B_aaj(+76lht`SXQoGl$9X2M}{r>N^BLT;T|W48j2n34b_q%;hH)b5%G5KQS*S6!I%iBh2Rg^QQ|J?xGFQcPj_gSfBn1NH@7nIt{@Gj#0(VJ<`#!{$L z7}barTUh84YbV;e$>w;r6{F=1a5BKQ=3NDaHyIDda`(rRihS ztu53+UhU{0Mf590X8QIxHnXi2TF6Gs`1_!F_)}L4DWbO?-t-RzP2}_~-W2GXNK*G| zA_su4K>gOkEB~R0CUR;5BO$4Ylp2ChYi%p*_ia0IUwXDKbw*0gx&jzSVb;a@*uOl+ ze!Qyf=cA2%p})i|kiGV@csdG=VM5O8p#8Ka=ZqN>2BX<|<(t|IAtE|56wUsh$LPl# z&t{JMSgP{=2uo_2-Fo(4Co^{ad-pPfx%*gp!e(2aUGCRsHy8BTm%93F%AS}`$-`I= z_q7~5!l50bfYFq7^(FsX_}YxYPFA-rDuJzwDcro$<}HY#z7}9 zOX5AsQtV`8DOqTLs?h#KWvf$(_GiZSr_ugQz$m;=n*)W=X9rX}WXaa$cEdUwHR2Su zMS@am>l9p_tJg^DMb@zpB6 z*!sdEeAy1Z>^Pn;5A~bmr7j&ct+JH8CnU zBa#JPvtb)X{nIhOHsi8o-nq+yWW@z~#vW}}-Sd~ek-t5oeo2nu+t_WH06HxM8w3J6>~Q87%O;s01YEMyq)rAs>ImmUYTG*C-7+x{ihK zdz0gnd%rA-1 z{N$E_(HXe}H2TMyWefk=V+}?wx$OsQ0$a?rkj{##X2@kl$=JwPB{XbX}%vOxtGHq4%j^X8>I8Tnfe)iZ! z+$j*Bg;nrOT12oG0R1F&Synof%I_BSzx35FrQ=hp`L1T~PR!F}=|&=<2grpmTci+L z29z|~j!>qvpx4W6bNa5Ek2O%22My1ThAk21Z9-KO@-`tjv=e#2EnU&{P;SlNLfb2> zl3Z>LePzyia+sGdN&O-E0QEyV8Zg&;i@HErgJ4&Pkr`5FA*S8?Rw5k9-qAt5Aa#P2 zhNs5V2mZyIh%I$~k!&%o--Hp-8$M3+cZ;vZ)3u1#y(y-DTh>EcGdN-7mipU;!C4`SZ~*X8CP7pWF>- za`$J)rkT0aHq6X(rI5Vp=8~ajrNli8iEBBb#Gxd);$S||&)5NuJLa$CxMTj7;pJCO zmC|?Qu>{_zj^h@8I&z_A2oflcHQL4;P!?s*4pYQ(jG(FMQ~`BErU&;8hU-r z-{Q7I5h=;NzJ|V12Csj;J+rMW^@k=YgWD%UUp6?73^ul&So$8M^hp`E*OI|EIaiu2 zd&;IZF(P_GkiMm9w4`ag-Ho~$PXE~nq^}3kw+qt8k)P5{bNuI(zzOe30@)kb5@-mV zZNjEA|RVYeTE4WE^2ZnCIz z39ru|HjRALh&EAYx<21#R>i0rpAZc1hmKq7cXMl(x_#%S4)Qm=E4Oyj+N}$k-3nK^%6?U zWy>r%6v>{Qf(9~w6oLx3MZf0eDML1fP?o%~c@Tz)CI)GJQom)z4RG;0k_6pv1n!F;t zs{LB%5y7o8)T6S7Ex&5NwnOTM%ivc^Km1BDQoJ4`#7uOSy&gL_rsl9b=V}f;8Y4q$ z{-BTF7MhaYBCH7ZM;%`-x+YO+(rmt;j12z%BxSJ4l|fugqsd^xk-?k6G zJEROYziSy>>5;+Tdt~rDIE6NZh==V~BsQo%l%A{1Cooe#P)j=s&3DcIVm?Kwn z9l4VFT1T!{=9;Bk30JPDFQ*KSEmw*I1-Z&Wt{^udUA7=UA<7lk{qmI2qLM|8q`i;q z{m2%u2Xy%Y?ZC?coA2#we?L7jpDjSB|EcK@;Z_0K7bR`oHS3s?IM#Ev16EU=yva8z z+X3K~?YEhYcd&ha3hlGHMc0;5#)&qahCVtT-aeYJjC{bTO8)RMqr+}V*bgScc6`f@ zpED!q4;O$S4C(fvuTNNE^vLMxE!={Ne*WV*BeEz5tQJ~|fSHe)(PlF{h}FoKvC~Ah z90Be@I5iEJ7V6#t`Do?({K3HYMxv7xOu~UlH=tE(dD-5@Ap0Q3os4}FCbTL$T9;wG zNIr7R2%BTAz+v{Xl@DXakhV_E9+q}3*26+6eI4J-CfDBARhs zq5ec98ntla!xN}8!TLb9D#_ae&<{H09<4tm#~5~h_XpY5u&=dg+UR1DD9$lB6hjz04sZUkAMPXwmK%G2EI#D2OuVkp>fAZxenlePY}DmK}L zC1-5jm|3ggl?-acfZBn}eLq*EMMIz?*&!MzPd_YuzP)6BI5L!>+y)_w_c=SA?rXmf zJDmbU_sN}3_hpdI@WBR~HoqZRbX7bNc^0)1vK2v%9GIM(0qLqr$Ge%YbaTz%gHIDW z(o{WUw-(@3Sk%Xw&}LZ3pB0j066P}A&Hse1$4I4T!Fcd0pF6SdOCYai_W2CtvW33@ zcO92B~)SuS#NEki_@7v1I!8u2WK9(e`r{R=<`(3s4m-#hRSReQj-(T$jsi z=_;$-AH#k;waY7BhaSJ(!V8_;iOpTr>20;UIMe1H9AVkJ&9URVyJwf$kHZ=h#ogUI zp{tiK)w-sT-hdtW?9~Le^d`yr{7p| z&fZ40BidS{2Y%?mu2)8Da}Q--8Lb%Do85Cr#LXE?hR?pddg$KamuqVBrIXGWtjkv5 z9{k4qQ^7jahl*S%@@mG$9Ns-8TaUHhDe$iZ45+n)bDO)3Ih#8-cbmAq9V^+W(V<54 zNc97w3kO~!PX<)mSKy01w&RZW+q-^RYU~r%1-VLSn(ivC-1k}RWnUn5LQC?NaYXI_ zKNEY)8F~=)aZiTY8SlQ8f|SN7-Q2CyUKNX{gOPN1D0!k?=yrSX!JIkb$uQ^4(VyV+ zU7tBRJ5X;FKXt@2g2!NjA}EYoDl2%Ny9PgHcHpC}GIX!8*>ul^Gt9(KhnsT(xJE{B z%m#z_tb2{S&AS3ygLjtPQM#pUa|pMG3t=fB*cvf|xyK}4TRwDr_kwDoh}=}eU+2*$#=)=S(eeLO!>{8Tg}*<&74TDruw&uT;pzdW z%k5vwbQZn$zQt0=VfW$ZqYtU|;`;9U#07M&DV4a6t0z%C?I8(Myw2%xYd&B&%G?z6e@{Ju+ma#nzyDc0U7k0Y{t2LZUDxA3Ambm$BTrj$K*q0Oy}2W>CAhf+ z?-u*zL6@`ZBu;O=(8G)2)5CcOflp36?Q1jAqtm|#Ze4C4lj*hVxemwsHgtE|7q13% zi`7fE=X$(9HaE{Y>*@2mgTC%7<7B)v@U0GvmT zAw%%;n059$P13K}U0%nH&A!$YXW@Ur@NTcybjGl z_+;^8B$@cgOH)+y(=`F$zuN=vrxy_!Pk2N;6~j3A%}lX>H^uor`13{71Ao4_6e2))%CjksiXWq5(w&p; zKZqMq5$I;UHpNfyRWJcDPaN~)Z(bn~Ujgw^@lT%ckBW0KAS6Dv-KL29;N#-&J@9ey zZB#tMvp$))Rq2aPdRb>oQEp6d+^jPupoSbb>zFCndlgIo$7(lw@as2eFujY!pL)U< ziGEzfLL@Os|1vSl;g3yknfR8&AC5ar-1NbBl?gv8-K+4wU;+a1J@_vx1mY_omWhAx zl+Q9>_?4p16Mm&H{A#hx6MnUr?C{S{@27n5pAz*Rcz<|C{2xzxGvan9|7@2`(dEOp zN(_47{rT?_-|&R{XQ_`esYd*J=yyTreF(!0wS|4Fge6aJ(x{AuwOPx#Zm z@ZF-<6TaIQzDF$bgzxc%?-iCOe6KJ31@To+{$B8f|5#k-3IDM#{3qgLo^XGA{)z~D z!e8;l|0nULCw&|h7fe9BD!%6lf3*;ZuYh<>eAyHJnlJnpqT3Vx3t#vfBIyZ#!x#Rq zVu~mHUwz?kiNEmV?=4^Wuc6q{y?(7bkpAC_d7kj!`oc#Xy`QxiN1%vUQ z(e4RnuU#;>tJRq83HOh`CL8NZ?E1X}(RkPD%TD``ZU=XvmWlJ7@HsNPTpaO)SBl4+ zaO#1o%_{K`Z3s(U)MBUor+%i|jEG|jpL92gzi`5-Td6ibA}+$f9iQS6Nv~CeD|Pog zkvzqAQ!i3&epH<5jK6I6eDN7)yhA-lwYf;-wedOA^J9M=-K$56!$pvINz-{pB4j7 zd2oJPZSEG=J8sTztIa*)2M)g;lkUCZAD!_V&?5W=aR%fCs6<-2e=I)bxb5`4B7Wm> z|C4yu<9=0q+>`#-gz3nW9sd{No1XAD#J!&Q|0>S%guf-0IOUCGB7Gxbi^qLfT;!x5 z)d1nYlk>>(Z^Hr8Oro?ASPQ#+r*yjS!6UZRL+LJKgc;IMMY-+ftMs633Q^^cL#$fJEVG)bUKldtr{dlQ!br z?bv_q*aNhYk6+P7`q|PDj;0xpCi~-WhCjn)e5B_Ex)JY}jz28Xe3t#j)XazwE8uQ{ zP1AgiJwGi+BEJoH`BWjkPkS0e5f0`og?(JS={BC3=i2k#7T7e+P4@kwkJ)7^r9%ug$9nC2N{;6Wy12%mX@oxT>>#5eOoyr~7d1vc|Nb1wD}&<*=x*yYa% zae)5FAA4x#a~9~$oQL-kVdFkBX`0apr}0JqEN$TLhRyI^+Hfm=5Fh#T25rR`R7xpN zpa;_8Z213w?7a_sRMnY2er6_+fB}X`YgELWfEXgeBt(ps)=2^(C`jawMQh81Br++1 zgb-Wox^+U)qU*ZYwJzPY-RQbqy0zWd)fTt4AhniSw+$9r?Xug{T19mG9WdIob?f(e z&YwHy9%hoD`}_WOKlO#&_rB-6=Xu}r=bn4#-uIsS0dV5glB0Y*IPoqghkU)xryb^Z z>ilk<4<^bNsC8k9CuM-fv2#*8zzExc_1^{_gM2GF&9sYcq={T{bBuCU)ip}k?jiJ9)cd~-3jj3 zf4!QAXqV%{x7((^t3_Y*r@IoPkUOeJwEMUkqIitL2)lQaeBdtLqCc0 z6Q;xN&zKG_{lfe~zv%a`nGX2`Ib?Z0hX17Uu2b}{JGUQC0nheB_6z0__6z-x#|`8` z$n=BPv1~_Php_#5o$MbEAH#W_<Kn%|*0od=cg)SQ(7mEW!TJ({yppz^=g9D{-5b=ptVd1Bg6b@~_7{59=} znm3sLHR{b&=lyB_uFm_uey_eRLjE4=;e7EQFD ze?eho6mdKBCO3@SZNmCFMc#_p0AVl&7M;{6t3; zIpk{cvoTL=c?~(P8+krs{#J5aFYeUx-Q=a{2QBxJpO1N4%TJTzdT>C?y#E!RO(*al zczNWN@JGv2$*bUpmKTs;itA4;uOeT7_Rw-WIR?pAE#E{Q$MK=%d&zMf(x>Hz$#GqA zK+8{)H(-9%@~h;R870dkxt^Dri8uYerqwb@#ZkvE}#w7iDA8S|T#Q{*_$+^gkY za-0|TY556qoDYs@d4PNa`eO_@`-2?wv!~@59}Xt{+P^H!&pyU8(srL?@A{BG1&%XgFC zgZgUu0rFj_ua+Ms$NaWW%TJKsD@4DR50PVj8_@C#q)@&|An zYuO|JBF2lBW8|2R7HYYH9P?4m4}C7FtXsQe%fi-=wKcc$TP-&#P5<-aS@M~e6_2|7 z5c~2?_3cgTS8wWWYhTs2v9;p{tu8@FQgXftlTlx_X35G?;pSG%iM?{w^2SkN=T^*# zy<*Lki$;Z=TQLjv!euoz>#)eS)m?0=OmcI_#*M9;a(5Iomo;taZtYst)wF5L#bqJwzRsm}M)*FLJa$?$K!N#h6lHUi%p~XXULJyL%^_nQ&3^r| zY2-kYZ8;p6t3Vw4iw?uI;o{crMO|GTT{&m|C9AA_f2t3pI&SL;D_b!PNh{eYXPRcw z)oa~vqvg_Eagt`BhZhC%iI3{8YHQwb(nl_GeK1=NGc})Xg(Hnp}r=Ts}IR$-rx*B!UWM;NewWJ&@qtcX9|EM}g9e8@4%Y9@96moR5 zI_?6Rf$^6m-$CN|TG6`shSn|J=%$XY8|7E}EU$)BaInnr1E94oOpd%92slbsb~kmm zDnIOR^bL2MpwzOC7G20eW;K>zmrZor>nv$buGVHD2O6SUK_? zB)eT4kdv~4AHr#?%=X#);o3(XxNGGBvv$cU%U|D=8k@cb(=lacikJlSPFJ^&k*iL@ zQ;e@37^2!KbEfi@hR4LEkAFV$i)6#is+a>?9W7Z)1fYk}8y5MbI%YvVNhb&5!nQ3~ zCbm^gXMPLhP+qhti*CSpR*f8Jy2tda8j+w^QX)l&1q&-KYJJ)P9wfvuvY*R$aPRM7aMDrti+{@Jw@cm%YvX9Gb_N!Sx$Lp zBJz(0OhUP*tCO{cM-3d|!y;$b%z>U6L?=5G=!W4Ghs7Qh?#W6yFr8y`*oH8}*jE}J z(>_A|B7rv0#EuAn9M3tb?;p^9{xC@LnDrF{m8GFz zwu9pww?UL#nOQJYtMaHm86ud6FC@>uL|}W7+*Zl$Jh`ou+X}groB7pJQEsc`cAnf; z%58<*%FTTF(dCQewn}d2$!(?FR>-Z~%%3k2<+e(0=gDoQ+*Zh~+Q^SLU!*?aEVuLI zwo+~@Eub-BGrZmZ;W zp4?W-ZH3yG>J?I5ZZDGCD!H8}x0P~Rp|(;zCe`KkBDt-S+j(+ZDYq4J%cn=9qn^_k zx0<0HAH=<9D~1t|V1PG4_B(>rGyQ|l$^T_bHL{cmC#$hk6MB(8X zO9A%JMq&CxJjx9Uuamd*Nr&*qbmOzJyU@Wav+$7R<2{W6wtq*EXMDo0zrSDU`F018 zN4vN^F3H&aHg@cK#4NkiryluSRS&=Yjv~!&L*v5*PCcqEJUrI(@d_25?;oGj(GGP; z#=imwFK*!#YCV?2A^?GQnE^cG6YZZ>!}W!u@=_?bxR~X52pr zyl%*b3|cXfk-U(6jy9 z2fQ-qu>DHFsaHT*;ragYIVjVqLo#@0ICw{aC(8qGy4Iu2=jZtEkH0m*!{bw*3?84i z+y142XZrU%XdC~U6rS&2zxIzhB!lOEs~oS6`Tm`+_2}PkQQr2C&t=({hRnS2I?`?b z3V>G)CAQxzaO2+(6`t=OpJUPvbx6j)ryRUE@Tf<;3$z~PyT%3mn*uz}S%!>%e-1tT z7jd1@06d;WiFYBm@o&At^Zi=@BeX*ulJT$E!P^Qv;~&CFe7q`5!gR;XFAJgc0D&|a z|6-Bzx=l5?OuD1{#;gj+2 z5(lr}^6&l7Htjdb@oy{eq#ccD{5#FT8?gMl%)&bljbOK53V6j?`nLpnc72ZmuM9Zs z-x>>#jfy0{{dQrT(Ld^tjDK%B{TsbJb9~fkJ(ioG#*5#6y}--Xe&ZaxV&IwnU1Z@6 zsPW?aHwEoPJJcZ=|Bg80rOfhgvDRa`PN)5*0*~*)7&86a?zCSFcsx(D{m_(t|Hhs6 z+X_EuhdLzV-vS43hvnZDT94%(#l;NWG4o3bc=0U$Jpw(ue|G}U%+Jd#yw4~+zy0>1 z-D!t9B;((m4&DLFzvWtwIq2U_z+()lA>-eVplAD64LmdcuCeeQPR19^x*nv8!#NVn@716~<)*nX|xv`f67D7=h+Q&c*2 zNXEZs9K1D_f9tg#@%|JJz(mGB;7x^W$oO|7c5MF=7G4{ajem^e1fK6-xAu=ZB;(&w z2QO*iZP0r3?+E(S_U|U(W$WK(p=bNo2|Uxk8!f!ADm>r6HSbaFM;(&!?;jn!-IjkH zT95v%Ljl{r1n^1;qzToO^bzRU{`FaSo1sCw#G9}1eE+s<|ENQv9;wp7+hgHvLB7G8 zK0fFl*H5{h4r?-a=R(i+Zy)et(Bb&I0o>sI7nG3X`xnEHS^7;KlEM2e^lZGe<=@A( zp6p+R=a0W?;H3zp$+X|I4&D&(ilIaQZUi^}J*4n_|MqDAs6#UTeZ|3x;si*4i1#O2 zkMh;01>0{Q@c1sPA%nL9dVmyholy)t(|&)7G~-`|!t?#R=}cvpIwXU4p@Y|8`FFF{ zqkoef|F#1!g>*xv{U$hgjleVQ*8^qa-%Dz|`2OXcrTn7~$@uq6XS^gW|30Pl=-)NC z9$<6fbSSA1czkEVknwLd^z8QQ1YR6U?2lW(jejwP=leGWH!Em|Iwa%YYzME;^6%4H zkL7wD|E3Zzi+}ezczZ1WZnN;VI{wYTWJ){KAsPR=9lRmSzdzG@ELX1Pd%yi=1CQ@U z8#3)T)0ywZm6_{>p^oRZN7g~?<7RSF{;AQi# z!|^X+`FEFvce&$VA#V224s}Szzj_C6kLBNAYCV>li$6A(8GloNXa7Djco#s&9)J6Q z=OK;t{Vcd?zcJWHlHY!_p+q~>AsIZ{wDATk|NctrvD_VnLI0{e^==%pB$@u*0X-Y< zDDZHpDE<2!xbg2Ah3ES>3eWd%>vUz8Iwa#?xr5hf`S*8PkN#btt~dPlO95|Jmi9Z}Io`Hf z?f3T<-q7UW_$xk7`9~d+@ox}%c76LT|NcSi(Z83R@#g{WSpsP??e|M(ygUoMGU%{B zz65UC?-6(WY5%B0GX6c};PJ--{UP3$wI1dFfXwFd$KTBC*H=G-l3m{d;F z!t?ug2JmQyIwa%YqYhrN<=;PPJ(fFP^@s1@Y~b-7N<*goraS%N0T2IWeIEih?KcRg zQQY_M-t(1z)FB!F@Nw=yeLDeW+V7vW9_2@!W~+u;_%}<>}v}7Tzj_=eJ*Bx$=)X zB;#MBgI91>rv1LD_2}QfObCv@DZs;jpG^OL9eVcoivlkSE&BHuxar?J6`t>3T>D2I zlJW0$2hX$o+pG2H-v-CO2H;&vAWg=L6$!;>o zg`QoHHJ07)L)X}yoFBBC0A9kknrW8_(6jLp7Tymm zyq6sR_G$m9Lo)vT((x~8;r*-D<9O*%cz(Yf0NxZflqS*A9UL91>hN>hFK4r;sRn#0(A*0I}f+5M?y_v?<`H*?s1(6P%0R`mNh{E>{^-HzR7 zExWvLLOqsSgpGZC6ade(EwcUn_bENUoeQ;HKDQP^!)m^XuHR?rm_1z=-Krx zw(OpOF7;^lX2))O4!buvcDuFRLC5Z9$F67DeciHKrRICTjyD0%_)bVu-*Tnr*Egl@ z{>HI86MA-i%PhM?mfeMsU_0*s-X@JjX6(kHXXC|yXRgD3XW>m%c)ou_+CS=$Or44y zytw7xn_7?k@m)Azk9#g8Hh^?P#=pn0WBbXA|o z-fqjkJPYp!PXE&AM-+tI8vnlM^hckC$NP%Lzb`udn*bi$&)j=7{@w53?XmE9AJE|4 z=J=Nc-qtMs-QwWw16~w*Y(K6&V(`{E{tamVs6#UTeZ;}*xBM%#@FI?XM}c>zf|6U) zes4MBH}T^HVm11B%FE-p&mPt$#Hci{!Be?J1sL85+jNq zgJw<8uRx|=6n}FsuDZmtsAB&7i>hLmRK_myyqHW^+lp9h{`~o#S9x)jO7IfnZ(g*t z9$#|F#um@3K2#M#K@SD8F~flqyjk6+v^9+)A&*%VHmjxRlhBBv+7 z2U9D_&#arAn4IJ{?ItHYe0!+|U#Q|2n1bK;I~ntgteBn6b;m*_!z0pve$mOpm$>00 zzP(Bx-!m{nS`Q`h?a*{6tiErUDwSNy*}NM)R_WkquzLDxP9#E4-~*fd-YUHqhwrhW z1MU)^%PV=}L|Kqel_%V|IDh zcXWA+Hm+-JX=!co=Fh39_EvRtv|s8qb!}{JZ`!op`_M(LRn5&!vDk-2O#@o<|K0bR z3gtLco6Es$nV#74!Yne62Sc;5Q#&zF9wR0Vr%IV-WW((^x@_OF_=0^MtcPP|qVMUq>0Z?K+>6bQt(z4&UGr zbB0?4=)MoBkd;Mqsq zvlt(L$HAz{?2_}(9DVAXWwbKa5#Pz8$K%3~xxV6kX5jhPO)1D2dcH4kLlWDvk*!>jJY`cw?U0!w=yB@%7yU!wT zA^r>*yYE$cetpe*EM~Scc6nW9+vU1u^pExBA#UvQcd2cc@3CaFdray1c9YN}9uH%Z zvHK$SZMzA}?gXvJa*g=2?RG+#jWk21zV%2zmT&i7ZP(1M#%?Y2Y`gqUh^cQBdDNpk z4S%-X2Ow~MG-T{fL4s}fkhW`PZDW_%w%tz4E*_ctcG=go8^a&z2!w3cyYELj^$e95 zhjfC;+X5NKTc@p;?Rxhr2k$1}-DC=Zn|dsRo?VZv$VeccaqR)6neHxT-UEr z+hCtik8Lvd;)`)*o1u}ecjw2dwerZR+FiAI>9nDoYtMO!yb?RMh=^DLdNVCUgKV%Po%x8LLY+jQ6w-|nRW&17m z?%1@h(N1k_e!OMOgsS-dvk(YG2#l z-0}{F=0fzTJ7=z9M{6>35;_0=r_Py6;oIoOWfewXhDIKj@1D>7-?gVSXSR2Cw{3g} zBU63*z#W^}&X@nw$L5uz9-9|eWJcy_=FE4;=Gz>b-7VSHT0=jLmj39jHLEYl{yQk= z`TX6n`S!W=RoQ<7o$o%Y+&HhYy=v=LId^ux`>Yc4<*1)kR#ara z-pn~J-@SkI_I?LpT)x9I`XAl>BMeRbVu!qm^zNLQxp@2U{VmkF;hluV{qg-qub6M& zJQ{gizB^~W%{g<+mUpi+UsJ{`pDOrI~kO2#S*^{zaVQ) zR13WQB|>;3E_GEX5lWUwuHN=izcCk|z2o80 zT~~XoG1`zQNEYKgxFCK(7<%E3^tqwalTCPSpg11Y8vJb@eWb8{@rfxCYg`gb%MXgq zNPqm%w|?`7x5f;350Q(q;=R$wu6!ff_(R#kq1h$rJouWoH-_~1UJw7GdI29|_Pw53 zUQl1W7iHxiJCx~}K8lpCdo2uv3}%f)jP133w{xkTJ+CC4JFg}k9j2U{XXF3(#IG}g z;s2la0QsJPc^3q`a?R)ABxMa z!_Gfd*}jJZC`q%e8&uieQ=F1#G|4SxDUB850{JF#RF&a-ihl?c;aeLS;(Lm(1@i6M z(b^<&G>~uJq)`}rPx0Ra`D~F4Meya7X9D@}$z)f34^lWk@tEOzp3i8REzS2l9|*|fL<{h!&ts+tFHSzB zWu=ezP6Kk0SO8_}^Oz|Lzeh~cGJB#ZTr6(Kpk+RfnWFI7;@cE7@p$>XBVVTVnO77( zSNw}L=$Uq(BcIUr*z!f;>2iH|LMne}`tPMGd6t+G@PD>=N!wHTbH!GTM>D12N^J4o zs1S%h|xgP#pKax}qhuIF}(XAf&h1h_~VT?tmp*vY*T8ybk*ON^7 zd$p{Gb2&Q?R6bR6Ha4i-)9=leI`7Rw=1B72n}y6*jQsazAupv2C)SWdzK$IANNTyA z9L{ak@=fHZ*A6Y;L5}+E((=9Js8^qsA0|hA_G$SEa@4C|%ZJEOzX2`3K#qE*wLC~Z z6&v&i{mUaqy`x&5Lhd2oeV-}ESI-+ih;Qhr&$q5@Z*A>dzG>0cHoOl!jJkRScC^|f zd{^GGU%O#-XH9c+>z3T_6jNK7x0T&n%)|H|c-6PDZPO?!s^0aLy3RXb!!=Ul)eGwa zAKZKhYZ|wMZYuAb!Hp!1hXB1Rz-TdJ!FWQ7xq*t!0xpHCcH95aP ztqq_trSkH|jHdrZN7dLT<+HV0x3;xxl_P9U5NYY6MZ-h+3U(E>jf#`%t}|j8?{Zi- zLwM2E%QrQ)ZqlE>&Y`Rau&*0@m#_2V+2RU@YjO3$IeL89(WG4*NliINExi0KKT9b; zIjKG;$u#R@kk;oOtq(d{A8WKe#CWP7S;Q0)$2kH2ed@+#&Y60yXCkH=N#y*~(|_O_ zfmAR>{v?Z@p2Df-Ka1O}^!)dY8zJ+&V0-r_XW!?Pqn7LTtCUS%W}MKF=XnyO6mD_x%Lz7;`AoT*lmQKZTD5nE`PckyI*$f z@|={dzV|tHXK1_TD%jZlykmFJvKzJRZg=d?&SCcxj@`JnYkV|zKjzqd)3R&7Pd*>z z@!uaGd?#98g2?tW?M#30-*0F0-oCkNH+IXQWVdr3I)nYe@ytsf)6U}*o^Q7kGA zGIrlWifwlX1mYQ8WB2z+v+WjIcF#nfv5TK|f%@(Q9#E|YY5qrE^_c@TmJEvj`44j!t?zb z)c%=YL&m?;96a-VJ=V9x!h03v@!$9FO$aj~8#4Yquk?JoGmyb{nXVO$U9J;uxAQ`) zU1mVn)MFX;ZM*z_l^OGdGFgY`g82-FeV8^~JO(?a~+0Zs28GV_=oCtCX<)PvekILAE5WgNml^)S}em zx!RD?_G3k2{cN*Q1-2MH-LGYW$gcu)OV33o<&9M#$+}k7I9cMP z0e7T(;1!jX7pt4#Bi{q})QQ87Q|p5D#V6GLZT$Eg+-KdtMY_3v?e)DbZVn^2{2=!# z`f*QNgm9T(lxV2B z_PB^F8524zE_mZ0Qbc^r!o3l%bMd$V+}G_GD^bHGO&ZnQ&1U;7K2a#|BlAAF=;DfO z1-$3oY3@jC9euw$>%Dk$FMKf76ujTN_=JBiJWF1IUryAx-_Vh;dI{Qsprk9ufKTl2~XmMlkl$W9IaCf;dHp5R1 zw~en0H%*D1?Wb%*%C@Gdu_8Yu{88wvn-Lr5r)=90N}m>jUh{%jI9Ym(PXSD;s&RLc zpV2c*FNnvh;ElYuzkDziKRuZ^7Lxb&=VXv2T2JCUKPB8I@tdalDcfX9Pt)msO8BEv zXWe+F=w}C~iND;S@OL(k;M;qq&wbzO)r(C_)uIhOv|()mUe-pE>rlTly<^!-i7_u`B`TDNwcsX?KizF)WT{^o5PSi2s- z795kQM=~v(dTjBD8S;oKJRY4WM@7LI6Qbvwb2`Vsi}e!+WUn7Dm^f~r@ObgWvDkVO zBLnQi!sFEw{{u(bj=CRWE4-BTOk^<@^u}`-^?d52v2F4&-g4&EWO;T~5W+EeGoJ(H z^*20Pko0i0g$K-0$DRt|55CCxE91kk$KFZLOsr#Xn7o>F93$6$hGLh?orh<7!<2LL z!pZmvuO?N_r*kX&ag!Wsgqi%{HqQZcuNO}=4mufqj?(53!pLAps|F0?uXKR?pJ=;^UjlKag7$&XmO1e z51=vEps|EOqZXec#=WPo)@9}?qMB2!XP-50ANc2oXk{t-y$0ukD9!~ToC`wZl2`Fe zunuQ}%KLsFE((=|UinOoQ0D>>x`gL~lyxqMlt4N*&}ok;A?JwGlXzNp)%0|J1kVUV zr{h^^sH`@fhuTcSQ$qEO5aTnQhZQ%2W5o9_7AhqMo(xJ1_!%1+Mc3b)17qR0kD-sx zyiq-yj6M=SQMC}GFmKh6SGX@S<}ja>VvdU~gzO~+`idz9o|o{Fsj*5zh!Ldt*fn@w z%G@|)_2iWGu-hfq{{QyplDu{@_Y^oUZFgke&bIT5{+ngqhq3WL<>}T&!Efb!Oim$TxTJlu`t%Fa9fky!gbsXBmo!34-4!$q?^yWhjEX z3QGg|9N`&?h||UM0h7FIl%WXj=KLU#&$~Mriik7C!-0I>g~?C^U#tCmAb+a36>`Rl zse-?ai~S-z!ZO6?yZm-ZhRzk=Lwz#k&lP=;Gv&=44^<+9lSO@?{-xqbz<#OtF62!4 z(u^tWMZ|gHs{#Md6MqFcbMNdtk%BzaFLj>3$DIh)-o7&6f0>hifv5=NU*P1=5swG_ zw^yGeeuenQKz@Z&zDmRc`BhH-#o{M{`d#egUn=$n^7)H2LlN_2-eFp$I;N_&^|kc_tHk5j>5) zG?2g2$-i3k2mHU<$-hSM+f*5{-##M#b>jX&{&g8u>_x;{@n?bjwN8Gs=nmvJJNeg( z+CckU@8q|M^8)#8PJV}I!#xI`|9Q+Y{@^)Gij;Y7WcIPcqA9$f%F6| z^BhqWo*+I9f0?i3sHh0Yr;8G8PvyT?yc{ThruY`hvOLd~MR>q`hn7Dh<#WY3$YehC zityl>_i8BfTv-%8PxJ-w$^`GBGhf-eKcu!M^Bh?eULt-IXrHBGzm|E9EDA3dkKlYn zdpt)Lg;$ClT3#UKtHp-`@-^ZDEzgws*NG2-vpkQKqVQTVmM1|?>|b+loyn!)W})wm z%llHL;p@d5Jw8;v8c&SB;C;`zc#(}WSPY!>cH%K)IW{iHkFz*S%X(riFV*r4%~?56 zIXjV@&XCX6Tu-azF)deWuBXd#HYTXNT60W;JQK1$H0{@ijSMRPfaY<{Yc*epHpTAv z4k6=O#&@cFn&UU)xM6yi)~naNLG#NsN2l;y6~5Am7lF*G`0*l;>53mO0-62k$BRI| zjxsJMlH`!v$qRM72;`e6Pt@@uknf<30kBK!-%F0l?AG#w=THa2Me&4C(yUEf2y;^>N9OIx*%MX(;z+Fr&KS7Rh z(68k~{Rn-i@aj zeb5QQJn%Rlf6LY`S#ebZmejzvB~++@9cwX+TJ|`GO!&y+#wE)eZ)k5HX7zd%ZlZz< zMy;+x7L5MFj*kx;Faw8z21Zd}Wo!4!6*bE$5kt|94{)q#<+iP3Bs(VF<82hx(H~h$ zuDo$eck9Nwj;_|a_6{!S??n8VU>EdfFuEsa524qqMz1<=^r{u3RAs|lsSb}*DyU5^VTcqyCZXcMmbPtb9hJdc#q2n+VS_A_^WbDVm(6qnE2sYjWy4Yq&0#M+KOLk90h(6jN@0FV9= zk99M6f2;6(|N4jQi`zG?B>XWhiUrv3aXiVBQcPfqD-#Yc(YT2C#ePj27sHoi^ z#SpUDU8eN>`p(vN&6qKEmq5?1Z_2Ve*|K|qW49`Y-4e%cgSKn#tQx!LICghfcBfc& z&qe`2_~WB7huz6a&#!Nbw#(nCBx831cI^7@wCtXt_1HhZbo#eFhu!C#ah1|`&7ELl z_pmdrc3F1$8=88w`*r*Q!mlr50lxs*kimNp3CQy6%il#TZ^pjS+l@54zP*-RJ0|Z| zh3DIi0q-+NGi2~?LV|7g32oQhc{X}mp=aCOZQ1pZM?Ly`2Eg#&xBE2kz6IHk!JDA; z{QB-dd$N3~Ry2ByxwP%}S$3yG*Vz3P_HDa6fp@LOA~SgZru2NfuWGyJXa6 zJ(k^>8jt?|Bg)%$2O&e%CsbcjuhR4F7Qhh8m+5?C_g?7PcK2C!XF->GEN9}RaM($T zA|spK>m9o@v|V#&-q>B|*gas`#cc@R?!Tyh^ZR#p4!eCy&#!M>+r=#mNyhGj(6j5? zZ`oyB9`#sX&O7+;+vPXROxqz@-mfG7fMeHuld6K5AY=DZ$L_P1-Ab)TyEi*_`E4ku z`egd|2FLCl&|`Vrf{|qGZg%VrSavUhCiPfuJT_4E>w9+&yHtjr-_EHsmF5L9J__UTcEMXjNPq{-3D#N=2_`kw9B{g$?Soz^vW&v5LnvFv^ry2kEm z?Azo13E-KrOh{vwW5OQK3E+81<9x-Zvj%Sl_U+@6&k5O|<_WIx&qJDxm$Lk8LY~3< zBpk5)D+ZYH32Od+x6<>+{ZwtYnMxpIw-b7{-5r+Q7Oh8rS2}k2PD?hsOB}mp+V1r< z3Nm&VId*qicGqh?+U51UUEf#^yVD%IRoZSFje?BbvmCp-EW01odbEpfmv&>|B)%iF zNbSlked6C6*pM6QVPT6*9_J=pDt4MI>e=&}(c|@**{ALi=q-fLhD<#cV#n^cUev>b z9>*UZEBfQ*KQZpD;=;p^_ZTWi8)lxQZ+KV0EP#UmKx@5aEOeWFUB-9Ua(a7fIc9E^?L#4yQD`+McFY%hcPFFi!bxNL6>4AY8_)gtrLyGm6K~c0 z=#4*=6vQ*OqiL_h=!MJPcy8}Y!aJIHnQKX1^>U)DX;vHeW;M;?8zCjL63f$XRqSq> zweIlH-O-vs5&AB8=VNG6*}fOPoUZHX!%xBVN4BB1WAo}!-?4qkR0eP1PkrbI<6%uPv6uGAijid)T5e*&1W&#oid&R2;vjhxL!6RhOqDV(_^s&oe!8 zxVMcSPT1ysv?4hUdZ+dL1hp79F8>$EN2GiLt3iqMfAx4U|~>1=H?Joml* zzep;Z&PoOR0 z`Q6y2#){)#PW672wpVTom&MZ!J?Z2xJ}T0Y@a?tnbZbxPhK}^4h)8#aBCmvt?n2s! zdYU$f!9Ub~?UfK(Y*o*F8$^05q{lnr>1937ZxGXe^v1vzXs-~1`$8SBO$oD9yr-mn zdHR#J;a5UUBE2sWN`JCu2hyv0Q2&rPK7}oxX5G?~r}aoxxns7eQDs`S?H5gLXg|Sz zcqGMscoGtI#?&)CmH+2{tGw~t<-h3L7)__HDLB}-5jGn8TKhH%aIsVDT6{v}g2vLMTe^88&uVPpE5PyM`Dk@{@ew>=tZ=BLH`)ERv5jwQ^XNx|0KBDr!PB2_!mtd z{mIZS>EXX=4|iz~#a`y5@-KV6_Mhz0^4fF%HBgZZrPHAuweNjS))+QkOR;4NFw$bl zLoer-c1@G0`K^wLp8?)_BSV=Zz~zRxu)h= zxMXueq`#LU?n8L5LxdlHEixHLb@;05D21?QnfJTUaqR0i*O)h1wuOKneW?$>=mlDu z^L|Q)+!6pf&j1tpg+1Z2F5lRy+G+c$^f z9?XvsZ_EI(McHM8RsR(7LVb@NO@9i#H<+rBy@=VbBGLcPzL$~9UjIK|p%g#6Mb9rU zyu`PVOiQD7V{U$ZLcqhp=bm{T@3w|8( zdS~z08}=p)q-ICZBjW~ymp|~p@lMhAyHq+pE;YLVxwSa=;j9wEyO!zvaCqVP#5f$M z`JsZdiuZ=Ra9^K18>#aV&OuUl2hWG$1IaP{h2`fT#EdFJWz!E9@LiQd2RV0*58>T0 zF%HKYhVmpHbCH!pUQCo1V>LhF6_yv{P00hOMMQ+lCiO?k^7bw{k!s#|VppVaAg}zK z{(^GvAW{-Y!P_kGv2Ndq!N`H+Q^|d=g`@jl8(aGQWGHrR-PeAfPCx!yO;flu{7Oxz z@At>kQacW9z6Iln=?7$sy64j`rhr+1dKcu?KRbjcT=gQIFLu;Uc!rXP{j$0P*rUXp z-L>)b9VstabE06}D6Qcw5uu$^Eb8m+o((oDPTAfe)s-_9vJ=c3rsX;LuKQ1+G)cpUE!-N~lx} zj49og!13dSrxT?XTDv^Chw{&amIG+b-caebbx#2`65bEK|24d8R~c^R-q_Mw$!k_b zUa1Z5SNrR@A8z@6^7|8en(a22R2oj8-SEy`IDC3Cl8!{`66EQ~r^p8fn!l4MN-hVF z9D61lZo=`x_GJ(%j)&m8cW4`#$2C($N$|bFD6Z3|=AmSshbs>Az8d>Kq2E|j$ENMu z|HgOIiaGc-9RaVM7`-!eYxtJP_B>2O85+cI{e=^!-Wj?ryd(1Iyj#cIGIo1@?L=>C zMn&9?eOdm~vV84CfEQZ%eD3O5asmg!NSKY#w|uIdSQf-2zHOs?1o=rPzt)k9AWy-c zA%qj>e2>fM7=DJifr5l=?`eI}%FjfLsL~PK75bY%e!ln(Zt9?kWV?n1BO@{tfxI)I z@8(Yuw*>MhWeQ`D?`3@=kdK=@7DdDv;)XyzpWJ7N>t=Qa^36&$N{8=NZ3yI_n<Qy1(u%@o1nxZ(&#d9ZWwc^`Q&_# zIkyzglfh%)wUno;d+0H6K8F}T1N9|`ez)d#YJRWgU~;|Al$LjDKBzg)#B-Nw&E`-0EKF#Z5|416Kw>3DyDycBp$2fvma z=?QSwr<)x1Zq=Oe2$Ubxd_3A!`la~-%`ew{o#tJde?jv;&A&|!KcClfTJy0Ohs2$t z`3%kHYraPF>oq^5`GDqVPWk=~sxHQ3-sTZRPAbnw9l__$QtQvez)9t}@of5QH)Pu9 zdNypo8Q^Tc+2CxyO3Kq!d;#09mg(S(OJMu00-rWR!isWCj~qW-XO&bwL2;Hxb)~*c z*V81^3v~Jv@VRqU+)oUgR6bep5%u)6TCNv3E7#L#IqnVeI2g|W15ml1KFiP1@84j$ zL(6xNquvi{xsM$6ep<`@iLL)jxoz1TmLW8|pULM^jj!l>U#?~mkIq;y4H z-CBFeR6lgv%HUfFd?#b=l1*HymEqTjzwc^WcSCn;?zK}1aOJWkx!*y_rI01Oo2m#; z$LkXEJ&F3R*3BwPHsEenjofGrbxW_vjTFqyjnW8|%G@wc_V73r!{eyz8$Q0Ot$9OZ zS6hd0Umsydv5%-AWUsZVefPbRT*1(6=em_E>jEpu=Jr{3#t1J(NJzfiV(SIEZL}!p z-sM}GZI~RMIa&c@PF@a#Wp&GKI{^eI&wjsR*~%sI)rnP2>)KmIO=E3iSL>E$Ej8GZ zez9kiZ(Xnr@#0c_d()QW(k8sI)O=%oSI0(U&N>uE(hR; zdw@qh;^DOJ{AB!Nx~cDR$G<56;_p*KfRV(t^=&*8>qGzei^||Vrtp0KdbNM%SC{ecQ3ub& z`Vfzo90u=2?Az_P8+g3VH)Q;K9tpO8anzT6L_A)q7`%VMzTJKaGz!~=Iwa#CZP<7w zMuvFk8XxcTaKQF239tkcG#R|lLC?lx>`Nnbh=*Mt?*@hEx8DI2qJPvO8NAI7-fk#R zk9fRH0~-gsqKU#|K7l{$EPEIdB$HF&)C zvD>cSn4VSnHf&&Rt*;rae0wSUwh8UH@x;0;;+m1sTo_s12U?_XyQ z|F$@Ioaj81r+?G&XX>lhSn&P3SNlgDlJW0y2hRhZ8Gq+#J<8uj13}gI?*ZUF3E7a} zeoD``+l~o?<@psmdTgi9;m@{v z1bDn(V9410ED~(IxP=!(p26FMec<{2y{Y}94$1iUQS94z4HjOd)}w!XN8a`?4+pvN z3EBRBsnYZ97C?{XtEdDrb{T7C+ikS$UZnL{4yOxg*Z3U;-Xf$KqEGyrsQokPtL;fh z>oAY;k(k;#xlf`VuOkc*i+vkwonCm-s2Jw9nNqEp1Ac>3ZV8J`fV#_FD!3kJM%Lxj*`JR zo|+A{qK)o~AaYAP5Pgr^KDHfJp2f=s+a zO2!4@nd`V&1AI0-^Waa1wu|Usyz`9yrcFC)C-+mvU(`by;&m#%hkeR?dd+?OiGBI; z^v_e&Y}!PtOJMzaI9_m;JxlqatQobK@ zOv(jPejf5Zr9YPXr5j)+Ahg~#;pd)VKRSA6()9p1*$bbMX7uJ3rN<9F*3NpxIv6dsg46|GL>qnARm zmr4+iQ@ppQz97O(`PNec09FqXnp=c@0@VJqXSq^aj2tY zlb05FnuxZlS5GRjTJN}@z34xIy@;bh>}78HR}V)E_Ok0}%%yM9lnEim^L)r-qVE@@aJ_wxf3L!5E(7M)0&a zTsEaYRCfNsOOm0|$@t>jwqsX?rW~9$a7psE$fQFu6|oW9j@?x=?%?T2g%;Lwg5A zb|7@&g#Onbt!`^L@fMz#zO}g^e(2?J5#p!3__6(o(gCJdxBcjiwvL5 zsUUt|l2K2LbeJ%pO0SbzhpTE|~XP?`ep6X!f@H+CsaINIAFrK19-p8k?9pOQY@@C0b;2A3A z+HHzg?r-KZT8Ypib4qI!FWRPfcz?^mq3s^Zbk$xD4IVMAiq~qsP4N}`Tfg5CN@Mlt z>od=dXq(t_!cV~F`ev<9A>N6udJ5Z39&tR_l+cG;|zN3NKbe}Oph juJv}{6 zJchIGllbGmABnHM^vuu>!K2{kN2BSN#2ey$p*+FbU_P%29ZSXTdkJWlE&AC*uZy+I zuuXM{^usAg9XAi&{ZA~785jufL2cucM7ji=XNJ>yP`l8=z5U6x$M(hI#|wMsNj9Q@YQK9o$M zXS(VC%{L>$iT>|mxcR}ev`2u{Ihz^F+ZbuYF&1shjIq3f(YDFcQ;{`$^QVV? zUzqOu{cDIg;_SssHyM*Gqh2Zyv4yCtgo$2b46T`q)f^Zbi0N7Q^OG54mUp~hjPU0C zE9Toy@k*o-bFJX)y7XA6B=X9b=7PEiB+k;sb+M-2whGLiu_hT^rmf`F(}szCj+Fi8 z#}ULaqn+gJO8@$-m}#CVGI7f&C*$TARmgI<#PnvhAp)@r5s2$1#~HDFTc}}g-(xQ$ z1}PGHInig$*^IwYGd0%hujP9EnKr38akrn>xvusY7U9#ms?BOn>@=|>X%Dl$9S2f# zqFCnjbd(^kXFa~xJ192i(y7rph(Uo4X0bR{RhH|dGbW`+#-{WH@a@=?logvIhKWs4 zu}w?;xV##~M$SsiLd+a&A+jmY3+;>`t|{!P$fnSj7}>-tjiZQ~OI=-X@TiR9JDNC} z6qzel)DsPd;GTXXTHX$t^Kc!DXqoVmWv9vC2mWGaAtZuFdpz* zWqD6uJtEf_X)ngIEqdx7{@wQU`l)&6A^vJSuJBG|HOvXx#hCIMIviK0GVj z%WJ3t5gHJPaI8pvKY!}paO}yUyuOO$ZTSoL=5fEbBDn-#!SG@?Ad>m}*kklF_ivN? zQMo@3+69bgE_=FPUakHGnq1B=ran889wbUtJo;x1RG#pOR(lemd3t|Bdll9vfBDe*ADA zDSql&4E)-OQ|=6XI(%#7mb~p_5S3-$0yqjRTYdt+y^DUPmr+((yV8<>26=@ge+P2Hk{^WJV#yc4pDs(D2>D}{Y%G)W zJJ>5>KSLaO8R9zX^8@)j;xZJ$Dzaw=@_EE%C?d|0u_T!kJ}t;lM0kSh4`j&8>|&4c ze1`)0>ZY1e;&-qg3*^rnJca)VHF8dV!sH1OKYG^eV&twuu$;p$TviNKKn65d50tC zJMuC3&m_*tMd2dxH(KU-tOyGWGq#HPJns}?VPW&_P##G|2weIN=2PbL$SVqa;s;vh zk;Lzce_qR#Ql2UP2AujlcNK+a$v8mDtad5lAO8&fMVaR;#y_$ShPZE!K+421M7dU% z=Q*ti@seEsAmd-P;JO4E`F-MNXh+IRrTz!RH*|efeQLx*$YlOZnZHm>fuodFdo32f z#y(}9tBS%`h|lVLRi72&KtNtDejAWii`Ia=M#ba7hi$+ckKuZ!<^wRon8x=)pM0t2 zoGU5cOAh_7YmQ=a9^b9Y^PIx`O5%WX{ULHvIod>W^!;bBGZ&rD_K$(z54>qOEWSnF zD8xSUtAyBucB5VwIQ2-3Q{*@yZmH&<(EL`-!35*^*uKP ze9bWp%JSE0`2x)`{msYjcy#_c@(=5HS9T7le6EhSM0yi zzeICPZyaOvcaG-FDSyAZzL~aOtp`3Wsp4^`wW;St)A-_(I0%4&wM`n52O8;YMIZ+ z!f5w)Eq9Wm{cqB8iX8oLhn9Deqd)G|axXdhfLVMt|`5rYzV0M!(F^GS|fjqkr5u&0wsh4ij6eR|mB|LT_?ZK$ewp3gMZE zK3lqS5rVmfjnT}ll|6V4`gJQtgmhF`9mcMmLI|gdooj6EYU@nqjO5IwWZB9@XF7>i zB<66nlH3bG3%H_&s&zit)P`WzKtU^rPy3Qvl?pH|!#qzR zv{M1DUDVap(KVV7PpwZ!KiJf@=@g4B-*5^A7H#cpZSHPup{-FC(?fTZ+AF)U4*t3u zO~|Aj-RX3&>ZHb{OIOw`saR_($}rH}*$z&i7j2lFdTPb*mE9ek7|)|BfkEIO0HZ39 zRof14MW1KY$>}r>iU(BV^ZI z6I=)Wx@&^BjB-tItcZ=}z+2`xYl0&*Sg#3All}tU(8hkt9GOt1LWA2fXWDM8_;zQFx9+91JxbnBHk@?xQI7e#e%#g&u$XRqHh5P#cmu$rUIKrpqL24w6tw*#5bw7cGI;-hblbn9!1JJ#z#lG! zeY|Z7&-d>-0MIUVNCxkd4qicV#y{Gj9?Q+aj_qFy;Teh4OF)Oee+=FWXi(cf4|uzfZ^+;cK+pDX4e&fDCGf}JaRzUX!t?#xqy3`} z$>2Tg;BB@1o1*ntug^OE?E{|vsY*B>?=A-~1w7U>fxq`^J>n%D|DxknyHJN@{A+RW zc3S>n*RSuJ=u5l(ih)P}4ViIuLh1SKGF#g3+O!?I+_8H=+vPnclCgW6V|R~b_k68KyPw6M-Ol~MV?P)&cJD%h-G2KlyjjSjUE;Ok z4|slmq_uz4AsPRguy5lXu<&?`#^9AZ<8KIf#wX&Lea{(xZ)&^dF1N8e)fs>NmR;Vb zF?Mgk3D9nrJWR~@(4Zz`w+DK5J)Q*~{)+_uV)!$7*C{-|UG4=Q+lx9ReA<||$U7`!6KKR!I8f95*D_&3qPE5J(|)Jx!RKK=|| zjWeDZubu7qz1SJgQ?=b{V3Ca7dCqu_T6THM&Dfpn*qxEXZoXr;THD2KAxXw=#Iaj! z+2#EyNqL>sj;unlzX9zZbx6j) zZ(!fX>$Ln^ruFC_ujOt3jsnm06|(*PJxb5F`>M8Uo_ZO(4?FF=)w0`Y+5HR0?qCkP zw>Wl(wA~eS4rJ{1ICfK(-IZF8^?l8;%L`Z}`DFHAR(gJY^PtD_<|&=A`zz?#?YzUX zdo}c_$8u{Go<9x>bJ$(&*o|ttYk)yAcCT{m?zHS)qxEPPmy@!8&3UC5csza#vG4g; zqy01KABLVy)FI*VjlfjYDFtk(XMAIt(c?D;%s$iiKraRxhD<$Pz>eL1yHJl_6ih&o z#|iaVj~>jsR&j9@2XCJ`M~Ta|9+L20%e>e{{#z|0uZ?`syy{V}Kf4rj3&>x8wi-3; zd!+22@m9-?-lM|vHhXgAvapxf>?IkAmKO>o;>q~f$uhQ%Yp5ayFBwNnD`U#yh_Za+ z$9d2Wd%cO!0QW*(-(w+gffPHo(vHR2`B3zcym|o(CFw#~r~yxeY7)x2Kb(N zRf_#!m+xfh8$(!a4=Zaz%iElQboxQ85m=wtOwY#FV~sn+u1z>dDJA_3dEt`8=KB)k z;3vHG#tfvA1Be|}-infv%__oF^?T^X&@73+I8+kaTmz}#V7R1aGri^-o}mOIcM*}f zIj^J#7`A`WN5t{Myb{@#qO1^YhM2#{Pzez05|Z8{4o?&yiY-(+esja-aY;tQ)us!u zdT$VmEmf1eZEW75n>Pg@+3~#JHmdY;DzIUa~{BA8TB&7wv}jq=!ApUnCMY=9P(q zY)er}{nE{k9gQ-Mb1%J7{@C{H{e4L#(dYP$nf;WN{=YG1u2|MwZFr1YYm}W7V`cv) zoekZE6ASJPZ4aNMXJhiwtQB(>(B(C+jmh7hwOKGr9X*Aa-L^WcQ2@j_#+Et%j3l$1 zO?+-|DBHSacVhz0P(Z-knlEk(Byk4MP(+Luy!VtL{IIczaba5m`N4@ig16H7&S8co zXLhj{!CT?Yf&BM4`NcAhBa>+N9LrA?*96K>&8SNJbLF~BnM6ETwuo_0%LC=7Te-xa zDees9+gF*)pA}eFi^~(+6v0=ww+6~{RAwk5=8BDhd^~uz2vIiTamYNTIrbTMGegVl z_EJ1p=R2o{cux8>{-{q&MfiYsgO-*4L=nOc^EpO~uwc+!*r&{~UW5gLz6yad$9hp1 z?XB}mr94$s>3miGTp2@0eT6?=Y}NQmo+&=0^*Oc~NApFUujJX{1kzbv$#dm(@^}y5 zcR(7~kE+%j%#Zgghw@oWpUzaI>kIO7oV=$&W;xcMoK&udZ8;7up5M7H7pYti*K#zR z2YEcYkJnMt%CP~J7iq310snjQdKi||2~atP9h1T^&Jh?!9r@dpGW}<4(n2k>Klt7C z>$IF8hg0oZ?j(o5JG6WUIsD$G<$KBDcb}FYCWrs~wEP4){C-x;N66v-Q7ykpj?Nv@ z@|)zvXqON;{4FF$y^6Ig<0Pg+$^CA4u63WTT)cMKmQJ;z)9^a>@=)2HdH~5*$vo_E zGIEs7xDY6LYHLlw6rP33C)>H7w?QfA2hmq#$;{#Kiq@uI@vfdgonQHBgalZ|uZ!lv$~k)O*$8}-J6`D~Af zou{^&*3W4cbGCGMbvLa8zj34F!;D*}Mb|DF=9#T@NZw>I+_UvC?K^nZL6rMj`7DA?f<|@ALw;bs<-cI0|@xm*9QxC?JAz6xy9mC6KXuDbnqF?6&OA(0VM#SZcWF+g%75|9vw1 zNu}r8rN1mcQ)?Q#El9WR_E~n%hc5M4ZZ(YBb{kR7U=R|bq$`x3Z+DfpJ4@%AGK-;S z+udW?%VAWC{3 zTj=?A+mXTcGQZ|bng2kVZTEm>H-!$8Yy_&9#9>uoy)-Lb*jxKKz zF1uS=T3fvNb1JI6RUIAemwHWI8=KpkHm&zQbWv+nb8}NH_F+*|56_!go7T07&;sn% zRnCcBBE~d#bm0p8!i`m8?1cPf1!7!y{Md6`5GP&lW{*-N z{HSO#v@k4uN@MSXzLXhDtO@@{x`t%6sb}iRYl&=Q-P3wtl5R9RnwysUzwCVtU{uwW z|9x*J$q+)A1XMtjNdg!GVglhyu})?n21N-U^{ZMYUoZ)Q#1Jg4tOf){q!yK`Yq5=8 z-Nm-M4OUuML4w+rwN?|WyX>mnvDLp2Z98COQ|n*vAR<{&N^JTWd~_ncSfRA2UmfOOlM4sbll>nEB_e8N0fwKFR&7MD(9}?|lOV&LpQHdQ2_o@bu))6`R51Ff$83_~UhqgBm$ zCcX2e(tnqECcVQquz62z^c@BcdJEqc*cyO;D=7Jkdge^ehq0M=VH8=lKS_R9lJfz&S5ve^#$=Z zdvNsY(fn}pTs!j9>f5SE9Ei*v+&!q?skNUHHOs8qLs z9`o zAqTyVdXj~nWK|EQepUv~+8j!weXI^b`=0Ky#xkr1QdYYjtwM3te>}DACVf~BB&(}0 z5X<_|dVg|{$K$CM`bUPX>bCt9d?NM?+bpY^?6MmAvup@@CG}8u|14|F#vQxUw6UUN|2HvKWMQmG@6O%JCI;hox7mSBIJThY zN#-dWhql1FU*jw4qcmplHK`6(C-$uxvHvQ@4vZ~U8ThPYrCB-U)$-Tzb=?!9hoZq= z*1Rk>AzByPso^B{ts1ePz}X3$nHo-+#A%C!Vn;NL#J*J{_7fOKfH6CP@szYAk{2sn zk*G~#->MP&353EGS;vA70*#0r`vpo{<)Mf-K89KOgVB>&yr2g^!K}_~@H;*Eo{&%U zWWK)BdeM`y29U+pqbFB1!Y9Fs+Rd^jo13XDL zeJG>rO>EP<@>W1gw=d6*;p^8iZ(iP4)E5^5UlAkY=ZDd;dq_F@tL2&CEzd`kSm?3- zvjXLnePhq2ahtUaixF4Ixwh&o&P@_|)oGk77I}-FkFY46aRSja_t^Ls=pE|Jq5Jss zxkJRsM*4;awMc>8;KA7{zX$V`|MW8gwa8Y)cj9{#r_T$i=LDbq%zOI0@IT?aaC$uM z|GM`tHJ7)l2R=VP>3RSote7tob)3C(zB#7f$NK!ovBXtAzoUkcXIqHh zox)yT+%Lu?PW!(%p|0pfKV@{MF(mFFB(Q00Q@H>6a~om9!6@CuD8pLz2O|fgR6j5F z$PSv-V)T(z*;V!#>ML~RIl5?#SzXs(xc-InyRc^LrQ$AOs(8HoL|@DL=u0O)ZpjI* zkBEE8fhg8iUb{ZJp&oaSI$u4?zVPZ%yCK|T4f=k4evi*C@9`8YIPp>WkHW7W%~&4l z$+Rcbj|zu+((^+-R?ejO_v{t*p`L8JtS6%+)Z@wR?DK6~Uu9RTDBpi1e#c)f&b<@T zx=Qw1Q7h1dJGMh&R@6s-4FS4)S?z1!cQLE|$o1QU8%71i^*nOu{-(_W>dSr9zr7Q@ zT@&^)e3{R(GI1X&9e;^fvZ{e$;l5swM;6_?MueUEY%cnXcf#PVM_{9Al^qx(ZS_lA zi4IRVCF`Z$3U9qx;#uhtI`b zs-fMi$X`C0%Rt@kiPsbf?IJv!dtO z>cqaMCb6Fv4TCE!nJDj9wO|$MgR}Uh2Xv?{06%i&Ba9hM6TK+uksx{L-5C2BEp*DLNDIF{s}$sj@F? z3|VMJ7WB4N6~)@Amh#?yV&4X~I-VB|fty(}rCeyEIYDkr)U>V2tSQF(h(FJc=HPt9 z0(@=f+Ys_hoc9s=aGmKwvNN)PIIN9L z&`^`)SR~1@8UL+T5P(apA}&*s~t?2=9n-z_ABU=#)L9$sXMKb?nI>ME3LsSB; z#Z3BBShP6Y;~f_6NgJj-BrQq{M}7*64muW5Y-#o^va4yf5{f=spB3%y^TmWc+yisP zK7Xo4?FGMiyRWFnb4K`YQ!eU07j>_j7=-SEP~_RFNxkfg^P=#>6suNwz|c2E=?ky? z6#AxwdeZV2ocP8XwEdci!Gdro60U=`X!-c{pQYW|;e~yoX=eHv(r% z`tI}N(MT+x@_vq47V)<&bH;e24zQFu;BP78QBd_h4Xt?hw9!RI(1Zde7xP0 z9nZ`N_hbwkohbP;Ub45X67x8&b!Y?1+H_Snu6Om^W$zE2a$avBOeKq8LB>=&GPoLd zT6%+3IKTE}$@8EkughqZusTG~BtQ9g^H@9aN$Dg!W9>xT(KtcJ5MAhN8L!iu5`KD9 z0=eDG2(!LiyuXpvO zHHZa@BJ%x(hy^Q${2$3{>J3)kRzE7Zp=tvnv)SGd*?_sxdc4oE0M|_FifKJ&Z|T2C+oY$eDP|UhzZ6i*uEoSokI7vnthQ%U|J%@V_wXA{mgP)r>;k5N1{GI(Dzt6c4w9ELYt+P4}R@QwBYc6 z!?tNe*OO?$aouUhirG0a?BAM;Bka~Q=y=me94}-!vBAVG$OSi(WyaEuO=20?2ACJy zQf6U0R?dsru8#eMxMq0-_A)%5CM%Q2TlXpA?b&|f?eWhPZ(BZfyfyz1jkozFqXryp z6l?$0F@zC0VBvi)+aA<~_qhUgbYT^)wesoRt~TWP%M;IOJ9b05*qR7w4~yT@2ASf^ zqxQrhUDm|mT^Bvog_-Dr6Ta2I?(=m{!dpl$_W6oO<6Ox)U&mfS+~;`#bXe>c(ZRc{ zf~#X5n!R;)_xWQxqGNk+ojboLd+fOI!;y!hbK}0WhjDg(!cHp+iFyB!5&7rOu%m;c z_tdkA!w;0j+pIkN`C{r=)`2{F8wr2+R2A~0-AN?rSVFS9Y8aPXxRM_Q9^nd1c}!w1 ztYZb@jW>q(-e&tpl#8B7ZPpp7z_Mf7V4upHMJ^8)2 zhH&=E%L${DA4mOV@vm5$V`C;3zW${j`6o{3+87H?tm>*n*|xUsK5vZ528!_)pzEC% zKws}0f&Dn<>sC%dJd@AcU+5d*7kPwuHT)Z}ZiodYT3y8xztl~7^5V_b$Z%Oa!&(?i z;1JH|}!a`mK^!zjf+uD?3-y^69L{vLEqci~Qq` zX7M(h7(eZ3Wi)_mXDiGC3uTLmKB>=CdZ zjKN+Sp&7lsLsy%AeXPcsBA88VUblhnz^=1AFr;f-8e8=zIaO>w-p_wJNo zo{1YH6!V_AJ*;5*)5p?=dT~F@zaQ^tG!(=wyxVtM{UE%98~4x*W=w2LbWpvg!Hc|1 z&)B%-^;U1hJ=(GHxOWcnhsu0vBPt0wv<|h*Sj>dNJ$5eLugyej*ad^?H%3vi_trUx zio86`fYckG!e1v}qo2wzWdrhyc*kht0eY&y-!dAU=3~*);tbqxon7q3Hdt(7JF}R{ zRZD~|djI;g`}8iYUgq=WKc8<&R$yeQ65o>i0(L+3w$0ox1U%&;G`JYoMG?lo!F8uqsv{1f2Sx0|ucevE-DRa;z$ zeB~qEX8pL1^)i?D-)-GtZ}M#Py8Qj0;Sb$kZP2ar?FQdpz5lD~LB7=Oo@wx{2Hyf+ zx0SxT{du+DHel;mx*qx-%$)2*+v+w`tm^SG(3oC?ayrh}48Gdnw}21ePo?i-ry@IW zx3$H-)3e!oN80V_n=&@~T$q2ZZF7LF+eY7!(fL&de+&2k{#1Gp?J_5O^xf8-_GZr= z-rLhQrEkm#We0RWk^RZ~*Jj?PpMK3Js;h2eGG1@fDA%88)6vR!(A#<5aO%sqdp3DD z(pm_5S&^S8tLJUzWs~QbI`wii#-)lsvz%^gfcs0cHIzL<_j3cs75>!qJ)`v9F2*Yz z^EW)tg;}iUKh4{B#NF0r`wq|T-c4y6(_Ox&cF@~`_I2GiDcy3c)Uo#^!9G=4T@RfX zbXh<5O`IxJTq*|CgMXv-1_rMuT08A&TCChj8O|Q<(AsGcSAM3EKZMz?e43dh z60M!~=%@srSk*!t^B@YYaOLYQO8U=YC$PR{BAu1k#hwQ%Xnn_(?*c>qIgHksO{8-Y zyV&!v06V4!82EKwF<+;4x3N;$LvR_wlgEk8SM*9i&`M@QUH+wBkVqcL?{fL4Fp-Hp zT3chjM;M*b!2URVAl zMt+E0`J!9RsSp5RPc%NSF+b(f1*5{Z4=4E7P3vQ`YmLW!6&@Dko^nlm+ zF8lRg##8>a>;YH)wMO|H*eqB64eT}8pX*57!2Sw6ji(~rpmsR*uqrm*RsSj@zmC1+ zs$ZRvA7!*2aU#*#Fp)f1@h#7l-S1S(c0BA6=5y8W z5hMRGw#!w&$Bg{P*-I|_A7?j$PqhEzY#8`N`#)}!|9iIEW&htB`McPcUHQ9={3lt4 zEB{F&e-G<$)o+iH{}j8{mH(8H|1`5*`A-}92if;s{yAvmKga&b<)7z_{GYQGuKb@H z`M+R8T=~B+@?T^>bk+YwBmZS~jVu3UBmY%qx$<8%@(;7`x$1w|$bXG3cICfj$bX+La^=5o z;(Lgm_>cWz5|}-@gjZ1+H%Bvjjj_hpSQ9l zznSyt))5RA7WU~(X0t)oGm@ukK-|%?cDV9~lBkntDtLx#zQUoje2?`Lmp?s5`E=`A zSAM#YKgjx%%b$ac{4DEXSALd}Kh!FB<(u~BT7Pi)GuJ48rbX+?C(@Zl{z$9Ll|Rzz zf&Yt~0wXOS{8Oy)&MtN^AGf~es{c6#ex5bom7ix#qDDknI%n8yob`1VKfx$J&icKp z{^N}N3D!1OzFGc!YnChje4~7c^&40HON{(!)?KdrX-57mtJIZ0%gCQ?z2WNbv#meD zAL|?^&bA%~zd_@jUF>++CDtV_|6O9>hpabU^$QvKbFJH4`E!l@3Tu)pzrxCw{pBB_ z-)8cQ!_p`Z_*Y%^op0R&J~4lqZ=DBzrc(*C`~s`X<&Oo1J&Ud1yXw2x+6Epb$+Xy- z0)Dt+*jgzup?-%D>*oUuqq4)qkmxUv1s!%C9!^>#R|( z{5m5)YCY@nPt?d?VZG_{&k7@dm35mdf0dDcqczTzf1{D#YW>_*|5hXaYu2B9qW@Bx z)7sy5n&8om8Lj=jK*kR}o1wM7Z@?`G0-4SEA?#z9d=8_Cq(0!rl|?nrxlF z%Ib3Q)z)s@q98nBe=)mMyFWv5dGjEVFZ@x;7Q5;=o$`dLEN&FJ$k^`yChZ z{4cUULNVzR{I%>?E`Pkw?se7wdTTD?k>qJ6m22O?X1nTJ#U{GyTgSfZs&AA{aMibw zH3E$AM17msZdt!Jj^DzL$@;f*ehvG-vc95zYuR0{`rXVvmhB_#yOr&A*>@ZJn#;aB z*m*L3MSE^x>s76aKk}eJt&p$?e(BLeidA&OgBBOaHfU{vkG6+C$G%a_xuN z6nXzi;61`BT}QL=uEc=@MTovh#2IR7;JYw7=L&L3odC+kaBnz{CKtWoO!F6V#F9(U>g1^b!w zr||EK>=Bp#msuR;sQu^g@~^VlQva2lKg=4X{#BfRjomEu({qtr``7H4^fx^h$+h2P zQR#1C&)X~{`#(MV$hD8MPVE*Z_19eZTP5N@F!&E${{JIe>1v-iyA*h2e-wYY_D8H# zo1bDlv>uT80j@vSx=!XdaQQQ>6BwAN{4<;%X?;iXzv28jRwF3o({q7bJI}hr1|t*M z`>4VHPU@q>`Sw!lDOvxUz~|cMTL(c2kDdkO+9g)D^tZ^LX1$K%ls}fs&$8-edAi@9 zYtOcBf>O#yw*!BP_1j#*(>;ESR~DU4D4+Y*o@-qy>vI{Gudu!)+e`2ZtiP51n9TDR zTNg+?gbncOtPL(cYF+E%S6JV3@vAJ$#ouVXBJl-YtA+4knV44R6CFa9;#?wqScKT+ zJcNs|lPRayMTl{J9KPTbb>bAU!6{W1sR+8qgI)mVQ2AoeDa0ctrxOqQ1>(=JScrJg zMWC5-8eRnBNY%M#NxRV3IX^=3qa;64@}q^HGtZX%xneGqiD|d1egS|Y72zPS*BB{J zjZDYMXrhIZk`PkSBuS}pkcvln?kcuiKy-d>il3pn(ocX`P-&Yy_MDTEbPB;AdW$BlQ^d~hM zQc*Q0tf*GfWs*iEr65EqS|$DY1sT7f)D#!sGK!j@7!)q&aRHNfTo4q+#VvFk@)XC# zpj(KCJjF4UyPtT(5ydgZ)AvBB+&(%E`A#|xdWd+)zd$_bE5t+oF!7*AK&jk^bR6;@ z({a#rRF%qQf>JrUvZrzo<>e6SiTG{7F~SMrAX3pyk}s3|TEpL86XSU%7JH>3!5J5+ z(nv*Z_yf%>m*vR`NJSeZyCcsZ{<#P%2MX*i@ceL*=O|RDKchpmfDY zGen=1akg8m<()}RMk@LTNq-{gUP+&lRQ{%*=z!!8ihBx~UxtxLMbFCPKb6O!e+~|j zeu@XuUrQAFTZuydcA`rE&+$G8@hCT+D9U}AsKWn+j4yO5!lUyJk1w1zBE*B5@kJp` z=bL+_JcTNqZ_wmio?J+AL9U~?=p_CnCgKeA1>(E#?l$FPL+wuTuM-d2Lp<<*Pdw-e z;(`Am@t`(bL-OgMB+t)xXX5<|;z0wHkNL+~;z4n$;_?(XB#%($_!Q5Ce;M(>rT8Iy zgeI3q=x}+8p9>I7jl_e}oq-E#EVh<-&^F?MyODU%9iUD>_@$i3$lEPN-IA|`5K_^v z7^?<#&abb2`u@(_1C`?K0m|D0{gbx`=;zWNz~$`$%G(3Dygfiam-YZIZx2x39>C@8 z0s2|n;~~90{>AY3zw%~aMXyQvhNN#w`ddlg#+ZfOO!?TM=pA_+!Rk6rPC_b*OWG?b zISr|(Pf~IoQqf0}ek>`IaY0T+D)LH7!A`sn^Eyx)C&$r5ZN!}9ONn|JAD1Yf#tA!} z@%~JFgm|AACx~B5d?sTXIknhkqFG}6p!^4k&&G9^%->1W&)Aca-$OK4^lOqoMEr2Z z`!Vq`;$iH2M8T6wa2tzJm5HaS(mNAbM8VTIZ^N0?Z;8i{&g=m0KS@4FG#}%bZkU2)KBu%KkY))Px70I7BSvG3BR5ANsRqK=64XCEUp(RzmxbW7_Vf07t!gA z9g+NdL@%Vu;6LQOL}z0hlKg0*U%heKxPK}6ZA4ob+bQ`U z5WR`9PRTz<6hV7f@~;#98e_eZ?<0B(t`ohWuzxtwHpT*yA4_xt&fk)sO>`s9-;$qC z^md%TC4W89&A8to`9`8!7+WiOdcVrv%GhSfZzXy+;z{xyM7JTHB;QH&UdCRL{9&To z8GB3eM~L2!`bfTyC_14R_mQYRKB5nyeI!4E=nk}xKK^t-TM z^6Q8`3i~C$mFV9x_Mqf<5Z#IPko*sbevh#|lHW)42aFw({0l_?0ripm5u%v)c+)}2 zexjKF1SCI}DCR-4B_AY;`Or0zzn&=OMXi!wOY|V-kCNX`^jZ9lPx4O^{VD8`{0l@e z|9MODM~Gs+^Or7}cg50h)2e0l%a_b6nYXHW&8bD_Tu~NU)3UmC>D4Xut#ylAv2vz> zCM6DFN~y9%S4>V~fFr-CuBx_QP(vsM=G;{^O|^9`OEtI@k_%SVRjz4VT{i&HP}P9M zDzCm`0ALHk0}z@w5TQ%!R@JpswbsqOscse8!�hNt;u9!`(|->X$FCYY8_u>g|^# z6Nl!mr4r$$l`Ge@R<+hQtxA+KJnAlAQPsFCA<6?Jg+MYT?$XH>&8cgw`YLZbx3sP+ zl}vKPa8+~bnwGlMa7hJ{V^!9*)Hl`6ZLDfuU00hL@f2doaT7I4?%ibh$&qAblEa*o znHz_cOY`;zylFO7aoY1R_{4= zpQ`2q5La~{fT*nf03=2I2OuasFaSa216|a0W=STHB95HcNC}oyA_W?EU`nKua#Ns? zZ&QMpnJF;f^^_1sUJ3*>M@j@EF9m{XhD4YqZKXtZ3LK{e5|S>UB>5?jcnhRJG4fI% zko!{rxU*7}hwoDqcjcrg4Zo)-?c`9&s@B$)`sy{Ub*q!k=;ZlzZc9s3i#9Ji`EV*L z7A>r(T2T~!lpX-d)- zsf7A-h`U zeCd^6Jb!g-Rm}<}I{_x)Vg??rYHX~gj8k3F$?3hCbPlKtS>m4k4yc%Ga`&keQrqy! zdwKn;`qk0I9C<)``4~4KNp-EG9GCEDsHLuI#egsp&KZz6qJ+=F<>Y@rWn7LNSP9dC zPAQ{`Q=E)sK|^N;-mRC^ucQm+x>gaiNh6Ge#n{!a*xV(H1^~7oJbge?(*`6}Iv}a3 z1Cp9D04dxw8GzJ+aDP(jR7a;H*$Zp0s%l(Qm$VU-v^pyxc~OfJVfWNBG-Q%md8c}oV=F8tn8f5J|?3`kne8*tyP zKU`{;0YRc&1|)}eapaUcoCC=Q7Bfs~2GXC^nm76vb|z8%p$cF056E57zZmyK|6(W4 zl^i==lay1)rI=W#jxXGgxD?^&LQNr)0#S>rq&lkh28KRH%%kra4|08S2;BtHd`6XD5$PR>q&qk2Gcn3Hl-pr{U#97WF^ z+d6sHEQak&zMa9h)A@E9-XrgK=noq=ubv8Ch6W~KKRIH==|03OK^9v-th zcpssFZeKIr8Yj^R}VCn*~) z5ps^+(J+?EXG%$>_aeyYdJ8qZ_!)k-uS z=0Z}n2VR?V>7{p~iX|2irFWW;bM!tc^$wS^N-zC7Sl3&j={*CoO7ETWH#Vvt(Ysa2 z^xi7u9KEkgy?9-dC#Cmh$mx13HNAMX%+Y%g{TvWZ|9uNgk$~b`Ro|ZoIY+M_8Prar zq^#2WBgpA`uhI0L4Ovy+7vU&f?+D-})BBu|bM(%Ude1TRc0x|q8`1QhtLeS)Ot)To zrwp$mISDLJ(;=thMS(XHIW%qrKvg}43OvWY!_q#Ip``pW*uZPo?8}#OK=(@w zcv%D_ld`V`a=LvxHN3HqCB1|8A>EaX)bnjybcX-Jn~77@U~-s)$Qv| zVIRGdrsM6=@Cr4&8iD87M*}$NAsI@_zNH3Ur-nyyqwM<_N_G2uD3{ECA3{#I?~sN! zNyB?X;5qiuJAPyz$xu@E{i}i3rQuDMa#Zez=%~7Vqk)%f-2Fb}bo&l#cr-4k`fd_< zj(yii`_$N>>|1Z(#WcJr8r~XFUuQgs0IwAJDyjIp(Wvhc;Q1j${e$F{eG3JiV;{v2 z`9WbS`>rtX`ZW8dYj{@}=Y<`>Q#L`&*$*4%g?6cz`Y_Y&j0KtI|d`=}nXq#W`8 zZk#XaUCU(c_L^~i^J#b&X?S~$^W|I8K9ZrN?AvYN`8B+Yr5xFJ1x_4#T)mgdFG9{~ zkGRyUzUrp*UIIBZ2@B$n(g;m&5Io6|-mOro>!o)|m*Kcds%-=Pi2IbgWVes`OgMd5hjPCB1W{Ea6f5znBE*dJ8qZ<;W*FD))+U zp5Bg(wK%Sl()+w|p3Xv?QTYlfsPz8KI8PUAdgnn_=^c*qo9<_Nm$hAD5m9)VLeBB? zlTz>HQdY^OLr$;nOik~6iAVO1!6Zf3OYg2eA+d-kyfcKHqqiCHL*=iOvPv!oa=PB2 zrWak_sqc&8yy}cY^bYHf$q<WGE^7h8TFwnte4=j>?Tg zKh*6zjB?5*!c+Ta3pq#c>r!tW2_Y%HXF(2GPCeFYdTBgY^`LjOb-iz)P_pyjgT{HQ zO~Z?7cxwcnV_yIlv{XNmp``4)(ZJiR;WbD(Dp!DULbtCFc*+-qr}jq*IY;j#skf1Y zkd)ptAgB9fo2GZAlq0>%pj6je3Ow?gN=onbLe9~VXW zAoZ@1vP$j^$mx1_YI<*ycx3N?80SGcA16B>{mwWKZq5?*U2Et)YMci5275_rkR(_Z5`pk2eeRl|Ep;5qh<9V+ya3?*gXFATh$8s2&-NA~>)jSG_<`z8S| z*?9Ux$mwy=0X#LH-lpMwL*O~~MWlTsLrK|pmx0%**|$l`k$tTg|8)DJz*BvP@YH^T zkaP4lO1*cG5R%fn403us4rzKfOF7b;hmEec6?n{sMp6*HEmquee-6!?lO-hlJ-l#F2#x%X(kaDDV7o4K|+RF@J}B`> zZ}}PS`aTD|7Kuef;msCuj^3F$!tRHptdg4vIbAPJnn@3hSKpF&#Gfg~7pJ~K;L-0+ zRZ@7l#`xj`UJOEn_b@2Q5#H~N@pMnFI8HK@6y8x|JUyb>_Z=xmc#}{-kAqI&C5yj8 z$m#WsYj}@ncxeL9@!v<%K9ZrN?6VBKJ`L}0q#W57^0@8u4ohy|7a*tGM;|Mo^5nnA zG`zC}o?~AScqB(Ml$3qL3_PEP_jgi`%5B0tTlZfD@U{_`80=j+0z*9C6p4$JZkaP5wO1-;C2ubNZh#kEi zGc~! zo*EB+uHjuQ@ErU6IFFHiBtuF0WtM@rS+nn-q#Tv|8x+v(8v#6J6XB`-zZP21n?fD12U=lz5_WOuM2n` zkfHh2o1m&5`vsn3U&kn6AIVTs?XlOuYx|;*BfQ^AIcmphv^x$t{c;cRz6)L@W#5+} zr`xv~cxt?Q8^X%IX#&r&@A|WaUXr1t>?<+w9@Ol6N6L|XvoqcH)dG*cBcqbCZzkk) z``UrG8A4RwqoB&ZGX$Pv-+QBleI!Fk*_UJB6<(F_-@8(d?3;<}N!@?Fz*9C6p4y)* zMrTr1V~E=$)zQ zJtpO-+%FBiSt;~BYv}b$z3-D!B&GL&p*N`M?Uiz*_gjYE5h?WEW9S_%^`0Q5NJ{V5 z4ZRhb-v5wtq_;QQ-M(W}=-zk#<|v+rXmM|fYub+#V&?ZCU8 zfMinf*DT~5y@lrrdw5~UD!q-6)9bNK(`!MIs>ftQZ!z$a=^bn6-6QpS$Y@P(z|i}k zrWc<|arF8Oy`8|@ETH&S)%RlziYVsPw_=Q_ul#(NQ{N9Er`NY#)0?5`{f)qL#^*}l z>2aX+9yavuk$TmtAIi_K7H}zrS~5U zy&alf`ZTiAd%vN#IFP))TMfMrLXP56tx}@&ZZ`Dp(e%>y&XnGJjQ-XRynw6&V4d;w z>qh_R)bQv#sS2;w=x?2Q!akCrr0k0rc!xARx>i(pON{tC1iS_T#kVRBE)#N2{FUYl zy=NMF%OR)7UzetrJ_)V##_@cDieehg(`?{9Bln4@db|fY9q%ykijhy_5Pd>g;XNbp z9Q#;-uupzw+QEC;!1G-#eAz2A&^ym;!S9Xyq7%x6H8b zJ!zj>T}IWn+Q2K+>>H!wK?hjJf4#tanhwaM?5hT^`>z;y^z4r6n}6RL{<3~Fg)!t=93*79<2e zE)joIH9Vhj9a;#yWd8FS*OvhekKUnH_WhgTzjkRK$xu@E{j=e}LJe<*hWF3dr=qHV z>;&FejwCk9e=i6*$1g8Py|bt=lG1w!yzZA`P49)sQ}w73^>FmQ0z5ijsig3(HR}7; z1mWk|hTbn4^_{8dy;#%RY@C1J1KycRDX6ONGUNQ~EfRX^y?08=zG~zA8`Sg$HN9`- zy8WC5yt^e9;VHep5^|28cT5y|>D#rGl-`#hr~A1=(;L?Go`Et{RJHG;z=O$7QhE`7 zuDE|v>YZ!o#qDgD-bzhxxu&;FoM#-p`+#?uqcu_Ai;eTlH5y)phLF1%bL4qlLY=bL(sIEZR`uh8^<6AeN|ReQVwykvg4 z2XcD*HfwkbG`t#t=lCUXzVHjlP*Q$bYT&Ka@D^%#?Z!N;5O|XXlnd{EV;**m)T>qv zQ+n?;=3#A`-X)seMaFe#1b8YoNwM0e_dig~sc)^+dzDe&ImUJ9W=$_X_0Ij`1Mb;| z-o_Mqa}2%BQm_2%w&Uj^hTd(OUi#iQ`GxduHT14cp?8C!cb(LGy;0v=480F(dT-G5 zzB9xfe;ZTieM87Oe%>tgE;aQ2E9CSzZP)ZhG`-Io_1%_2Z>Le;?NV>Gp?9BA-<_J? z8cpv6W8B>VJk|Hm3{G5)F~;3TrQSM2@7cz<+o9>DciU9^t~2!hAcfu*L+_JPZ`9Dc z%Fw$<(_63UU2N#xmqPD6L+^7^uUhp^_20RM-cC(#qo(&!L+=YI^gd+heMRbBWz_e6 zL+>F?Z%n*`I3b6r zv6GbCGqQbE#tz_RQOB1_)#GWS-D0Rm3>}WH^S*{Z)jux5a}7176U5FLjL|bL(l=Pj z;grfQD49`Q8c3v)>C>l`7SEbeG9?fw=7+_$q_}wc^yz^>$&6W3k%bh=ymjvUa?2t_ zk?_TLj<5LP7x2BbQceoleaLOzy}5%GF6{D_Z|l354Jj|&%K{twX0t%~C;##BCpPvk zW`StlIm88`6QbXbdh*3S8^69jFP>$sud0u3sLu(nuPTc!IMLTq7H_l4BI~0so%pyV zFWzje$9`En$Z1Yca9(iDdDcBgqrW_ww(OTj?K7>%Gw%1^FObWkRIV&ihH{ml7Po@M ztntO=zK-VoWIolh`BK^w`~KbDa%FAV@tj<%At&VPwi<%R=Y(=Xo^A`6@J&S2i{()* zFZQFRet$|l+?dO=WNkC@*GD^#TXs$`eL{NIt`FKS@pM_Rk1$yvfkAdqIVQ`U%9fMM zS@{QnX}xI)rjSr{$DD`vEFR5Rj z?xTN+K5El>lzH=pHCSR)vT~|(8hl}Yb!8*Qq%sy*So@baSK84ojBz&WiV*dJ{yBC% z6Q%RpGZCV6cGJ$JpJ8m%`)u3pZGE$gt%;ap<(0%1^puS5>SM8e$2>zb5C6K)S6mQp z_Phv6`y<2H^Z&Zf>!*3pi=ech7xy~*Igp^ESvVTN(JZmw%NEi;%WK2@)>q!9jrsp+ z`lU{?rA*q=pZ@UYRR6LSIM4Gr==0Ty{mh!g{$(|$k1)ea?V|<@p1atO{&PUhJKK^R z^HW;}ESzg?dqx*Z1ng+&1e?D&`f{Hy_S|tRt9q`ddw#T_x7kw=&Wcjo7KB45J}E_> z_q(CRkwLFNajb1Yb{FgqKX;sY9t!!ovSM?v2MKUiSM^+P_npzn@ix!M@I4WnCG*KL zv}?d$F0MM%^^dTH;wlvDK59?tKFVIq?_IYD+82)sR~-Lj^-Cw>t35s0o=}e`JF|XL z?^g=0?D1sf_uiC$d3~rS%N`ZJt0BL)H6JAkAd_`hJ;f$!6oNJO{d4E{c)~-w3*zfq zx{qeep4Y&}0&$MF$6A;ZE{L<1oN!rBmWSoN*f*zGL|)>$D6Yl*WwBw=8_vx*KkM+= zzrCt&T(F3?oh7two zPrBFpZki{f>)vPqG}|9$AGcADVRHsAJ0nKYR}4t{@?|Pgs1k8Qg`IK$K8iq-hb8-u-f4r1P%9 zHScem{S5Z(-vXvXrF{$+*JD2HBbE z*(}G(wTIhhu(PZY)<|oVb+$FyI@gnLjkU&Gcu|bun}y7xM?3rx9Nl;M1j&oLHP*W9 zEZj=sYXO4r^dz>SZ2#TX?e-?mMsFy)_~d8m!=)^d*<9Xtx3$qe>Djw32N>WAxq%#? znL=Jaj@J;K^ldIb{BG+G`*zPJ@5Z!H_6S{1kmsLlX9&mfSjkD12H$G%TfvWTr15(h z1Tgp49o%28y!#=i=jnR>tMraH>SNY-x{)6NultdnZ}WD<%MAlL{*WfG*Pr%HUdP*@ z$|0`w;}2@b_4Y61?Vz>4fltrjbbS<$I#1)*XW{kd4uImRP&?>l$39WViF)wwkZVxH zomwqB6%>f-tEd)Bdw6}ux$1fS3Vx9XvxEJSj3f&o77tJurt^^S3Vvx zYRSV!vUFEIUJloi2QT&h!DZ4pS}xT;j~#a9=Nb9q*g;o5UQW@HhfQG5xb#oZatVJD zqu=`{(xk*L_B`wYw%L_0ZWt>e51YbnbmdP`S)6*SAMyXKacHm>7QrhU%|fP%D=+MU&uDN@)sKU zOV|om{t_eqYPQ6ckC(=@iWKV&vDb7hL%@ zM*ea}??)xl^29FoJZuH~vCF;{Mt&3fYgc}gk>A4Bx$;|#{57o3mA{5v34W&|wZ_?_ z9S^?1G{Yso*2uq^^}6bFvyp!bd&8A~i;=&c{mhlW-pJp`e(1{IXyo6)I$ZYMVdQUN z_qp=782Q`SbPSOg=Gl|@%e6g>-g6_K#_oJOg9X#DBa;!)fUkj6Xnycj6d8~vC zmx=Ja1|I>wN|YbcP65RK2PW8r7sOw#J&r9f?E3)6DL=&XCouY*Hu065pTy`pq{O#! z{sM+6CFi$tehQl_@oA2eYfocm8}{{3VVTID2hsj?h~_=H_AI_uJMlt4#y6M#Ap1o6 zOXv@?e3$-mc0%$(|2%fN3;zo4N5UV^^(|z-lI#ow*m9XK_z3%!tUt|Ra_t)SRVh#Ngj{<$`=yIt!Q}4_Wjx-(ekSWnZp*jV zvjvjhz{@wWcMy-HpXM~VSiBfN58^!a@mzZiyG!O@#`(2u4EhJj7jyn*_9qwqMs}W* z7y9mCyCqLyk&DHLM}cNym@OoFjrjIR=CycNjd(e{7ExiOB48JRW?s)(Rzx63MQ9T= z1Izp}XIT*#7Z2y)F>xXv(+*cY0;N>uUkG|Z4P##bEe0(ozE-?5RSdd__&Ua}qI}S0 zpqaEmDuNP)%j*@D$A?RLrlcbzB_X6DOd6+vUa$(kBLpo5CH)tmvxkTWy^MJ1BmJbe z8kF=>Tu`~M(Q(iX#6$je;z92w9`g4S5Bj&DRBjI)hx|S|4*DGNkUvB`XczI2KTJI6 z5m2X|=Zb5rOjW-CGLee%B^@j2cu5QYo7Jz#sGpps6-}1)p>hSQqcm*%V|;3VsYJQe^Fd-+qO7Q5D(Q@+gN-Tk@)$n8&lAldQOc^ZF1)9MSici62cA z@l+`JNkmIgAIZ-qiukIO{1T#wv#8`7i6Va5B#%o}W}^|eNq##~#812AA0-+@dq{pC z(Gc20@~;q`gZ7YoFHwpw4=C*Q5=ET(B~RbqwGnRt$&V$9xGR=?DN)2Q=0_ z-b5pZTw8Nh{nz+n>TI&H;NvM)(t=?FUj)(-R-t{$MF0~aI^abSp@7RKRu`o96-yR5 ziv!Z31z~+DJv!3=vUv%67S*k+YCgq^gb7KlbGa9gOBoXame*nqR^Fop5XA_hFF8jB z_p@N!(z>;iYuMz~tu3up)u3NpNt7(ZATyvfx(CQB`Gk1yYth=}gkUI+vHUHP}w&Buy-(DY}maBJYe4{hO=?iT)*Bm7|tQ zx`0-)SaAeXR#0nGN7!&$GLe*ciFQu~mqa2Z+R2fS3iT9{DbZbiO|^8J=~i7XC2}GR zQrVkCA|;v=DXG9*0$3MHEQlsoLQ`v>;V@sSOs-^>Si6iCBx{{4S0YQSJvNmu6(&~_ zlWT{a`Yd#5OVgTWxq>EN5KJr{CRYtp>x9)#p30Z?lB<3t*7*{vcFE*Qnv)Hi3h8o4|AI z3jz;^oTT=@D&!o!bEIC}V&F;XT?0AYFRhy1p^#L5smH$F9(2C|m*-AWdg)e;j<-(3 zqo?>i#?9KX>0ie&bE3vxQ%Rt@hA4ev%H zp6PxDwHwJ$QueJh@V0As`1y=u-~H&2fN<>F2L`t%oTU7BFXVLlc4&C?v{w1AR^U19 z+biu;Pjr=i5d-g04Ug_!E4-)VeRPQPME7Ho+4mF3>Gu6V!^5tFw?*JN_LZW7hFBoNnJf-~}N=<4Yd?RDG8VJjXuj_oRnp zC@K4D47`st`wFBSl{*Hdx_xf}FNotRf#vCUkkjq+;+~ryIb`2B{3-hm2t3C=x?e;`Q9#$b7I>8si-^)YLdZFK4@teaMaYxVI~+T@-m#kA^C3xc+)pC@oc`7YyjB6l zw@UBXMx4$80F}Q$$|}8Q8F4yE(@W!w(t9Zi>-C+FjI9!jh|+6*XY;VsJ4MPWz2BcH2f*NVFJ%-4|*?#{6aF6lzl@D zytg#_W=J_IcP~zOx_!mKyPtq$Quf^qIo-bZG(376L)o`n;5qgklJ=1dC1oFd*FwkZ z)$lHoa%A7n@Tc3?1-uZBsif@NhXasv^bSW{Q2C3cpwhbsysq~nP45?wr|R(`;!@W; z8hFY2M_kA`dK;zQprQ9Y$mx2$7(}`MAy=m9{Uhq9>um*Ivi|W0A?N5lBK3w1z3)O! z*PEs3oula;4P$h@ao{EEAGt!#(M#(9Q9a5Hz1cXZ>m9D?y;Rd17kJKiun~N+{_&oH zHyU_5fkXXco`(0Vz;o<-0Y=~umjQ9&?|^~#oMsu1r3iL zV=26mM*nC8Pxi@2U580^R zukS~|qq(R`s=iMPIj6p*xF#dL>dh#n_a7mr*Y`b5?=_HDdf!8T(Dlv+UPLJcReFCT zD9KEA)aYFUI!O%Mha=PA+ zG`(Ne^i~=59SgiYo2R^d<8_nR=zRbSveB(aDnKi>m6 zy&hQsaa}=pHTY9_RRYhkFE~W#B^gSpJ#H}YW(N}X)k!(>=W5|+XS}Ka9!zwSvX8#K zpxZYmkic6GX=NXcb@=btw?x`UGL)2kAp>uIAc0pe<;cFD3p~fZ>r>eGtbw;g!&{-@ z-7oMQ`=Zi5lA)yRyVt>$dVlCeKXA+S04e7#!i)#-hUBtj^6FKFsJe@Qc&sr736fije&&T)sR(s z&%i$F;na5r@aWmUN(v9%+Erg#pN90Vk%CGN-O{DEHIUFt{Zr}PWYqTs;9VxMh^YGB zY}9vzU*N5kvP$n)jQXw%B=mk2vP$nrR79_D0C>d`i-^)YRLD7gu9SLjma4D-iAQUtSH-gYgTR|B_lZy*{jEU(qAI-s zIX$VoO3ZWczggvx9L+OSQgVajJVza;^^vYeL6uZJ(v11blL7JW44ntJ;ZN1$QphPE z5ytl6c&7%AC4E;(IWigFk(nyK6cga7zwgLQcfLB)|952QUMG_C9hnT${<-|ds~oUZ z;x}G&Q}|Q=#w*n?yvW={Do*UeulNnhWO@k3CfDF~7W_z!O{Rx4+B*y8HX|$?wY3u5mBoBTy6{p;tgIp~f_;=jZoSF)%I3h}aXnvkbB~?Vl5uH~^PSug* zlEryI%7O4iW51r1UWz3>&Pk5qOeG~Z9|!cf>;fOaALY|=vX8J3m(!+-kQ`84PMKaT zBXa<88G-^WE`I~<{@v}nyyd|r@m-^4`CX&2fynYe)cs8$3*Wu5@Fkx}gMXL!N>E<3 zA{yx37OaSDjt1gIY;%NvN5c-3XGZoP@dx$a2kXCg?7%mG^6OtYY7b-4y86uUD}AFo zi^6Hq@)Pgpym;c18|k;U6N32G48CwwfnP4?^#&J?43|azrv5o_+d`uc;99My$V$RUJ$M`}=X@StHaRc281u0dHkmzkz>KKw>GtrLHqxX1cpUtZ<5&>3C( zK41&Rb^Fd=5Jx*7|85&;={$ZU=iiT{#nZ01YDeXc9XpmV`VPUon3DQNTL^Y_9`Cid z)SdZvo_*(?cLuoBa7SvLTk7KSn}RppbkiIzH7iDlR=Iy~D7FCK7^sfg?}pg=5LvPG zSHnDi9lHLo(00vXuH)*dS6_7X)mK;W(xsv_-isP%58wd+su_<|Gh8?E3) zU7hcT7`|el$y((k%gPe6ZBO_M$NwrXdMLsI1u+(Q>G;^7|J_9lzgf1@dCBUimCbBA zR(1@*SU`5C5ej2C*72v~(8m_Fe-ON}^Y~Evp3vc6Spk;!+|dy^_zube>O0hLsQ=Kp zlM)?k+g;Z1e1@+J-#q9m>|BiBm$Rv1{Qh}yWJ`wcRXRF}A8nIIFOx@$#nA#Gn<`G5%FaLs#C}A4fy^P3&fU_kMg2v<(bjk zjI39i;8g8tU)htUrt~8YG!ta z__7S?`uxU(e2fX3@x2M(DaVG6-G?y-b=G&Fx18D49&O(nX;NQW>wiS*IB7&;k;I5p zf$tQxVT8g+6%VjN_*5UGI)d=l0aTgCP4n&!J{F!)o-M!g*1z^9EU(5tBs4(iS>r~Y5E>#XwpUE9&(R-p%9gt9vJABo>aUyy62emN*F za8CJiee1SGc$_`jSK0h%-=gM6q8a7*rrXkt?m#^&9DSg;{L1o<@^tF)apptWZBJsM z%)>Y@wBZX37nQSbQWPHEJ9*cceb!*a;--ukJ211)#(vZLO9Q@5Y&?~)W&)kX-U*Zk zwQ>}lPrO6X$pZiI4z-SGAJpekZ?vsER__Z2M|FJI77q^EhVlB1zQ8tWvxmwD9kVjn zfp6^M+WS~=?=dzsFFL%d{oPDfG1q^%B4f^hSpCu-R(aMdvHId*+t~tTXXvdi7Jw)2 z$m{KD4n*3~Vis$U1OkWpTAAM96aj0)Cq}H)Oo)uw%&G4m%qq%HH zTcnk@ozxcJJgF@<;Rp*HS)LylUA~jI!()BdG(XmNUGw9p{jOcRj^`>tc1`0`u;?GP?!+sT9Ndkdp%a@$tclfiNiq@yJ#pat1@lC@^S z9`;+b(oVF}BkyrS&!iWRS zmv;0m^4IS=*yxFt^w|>;U-_dp9jv9J)-34pqfhX;OdGyMXz_0?S`odU=s4E`$ByRo zSr-laR2a9NqRwS??S0pv#@7YbM;G$e8_ZiTtJ|*6--|ZO&5YUg7w-KeKOJ<`u1oUK zO8ID|{PsTFU&?=Gd4B$e=zebF%ddS8V6Rps~#K3YaT@?*5y*6fcw`;PM8F|Ge} z0L_Zt)|5YSO!uz7v7OS-}(ZxqWF^;iud4V@;F?JPWbSZv&InHvc;^Zs-4II!c{AIIa zlQKH7kH73Yj(98cqnm09r%>DnclmLi73W17g{*O1?*yX3Jgb^U-1Uf{HhiD+XHFa< zJ{tx_?@X^aK%SxaUgT%d_57=T>y3!x^OFWH#|H<&ThVY+SKr#sEz#Wc%vbX!`nnm~ zeo+7(ig((XkwAWE`IhLSbpNaSj^z&>!gH?+48{y(+v>rQyYS^4%X1fRAA8xsrn0!- zI!NONKeLIklfDfo#-3s2nRF)bPS{njON>46-q--nA(j{m#^wha>M-IIzqfqn@*~1? zyjLdooLxB~y0K<#iSpbLc#g)DKp?u@8vF7)g;8)p^t;}+8!ddrlD^d>zH&<6Jbgxs z&y)R#sNqr4rbQt|V^Bt;yN+#!UxiOG{`jp4^xdCxV^)+roCXj7zxLh-zRKdt8=re` z5<)--5pA@HH~cdqlA90^TiYf90w_oXv~+7t0twvIki-xayS9yrHd|iV zb+^$<*KSc`)h_K%x6x{sc75Bl>uy2qZlo#8*6#ZIerM)9cb>^}A!v8s*Ol|h&CHo| z=A1M0%rpOQOEE;Ep!dbh32H0Oxqgp?>sv@Ls3 zm0Z0++ZNb({6G@-!ScK!&ByCK*wzs6EetG*KbJ@rmP{N}CAeb???oSxOi!E^UmyQ0 zy?Vy4m6_@hMbmN_27+Z++&HNJoHJ4#4Eq*yk^6% z+RlCOv*}f@ENUgiq`$W1)(vbS<6e|DoYGeqS3g#WvR=I*R+3C#gLXas#cTB4at-R; z@a#dI^E#=)yC0;js}=3Vib@S)#Xk{!T$^M-Fq5~dQtzhXo9xrPn5|aqbcvcuys;*tX)&LnR?39u(>X-t$n*aHiTJcz9t?k*~=Em%)()=wgD&5K3wx>h&P()QC|KRKrO z@uK1GEx7}+>EqVF+Ri!3tDCOH3VJuR zcPzE6&x3xozF_?;?KMNm_$!-UX;-tC3>0ETSNu53v*fvb=rh$&sfwd_?Jj=LbEU>t zEoRZ>gH?HDkW!`Q46whf()}fF(M_ebEgPjg{#7;e+R}~eRVTeD*K;5G((v^xd~hGG z=f%J7d(_k<>t=SFn*Hs8(%Rmor>7rs#y8$KypC*V+1i+U4M!7KdWQ@_-elS*2FgODyPp*VHu>_X9+wIcGS-jj?Q1)WER3g148lZ=AS7j7AA!2u(9X*LUUz2BQib{5BZ{N z(&_L;XMC%{qg&V)Sz7XKkB9uOb%*ms(~N(+5UtY7=a(l5y1@4lSv+CN&9NKeJ&Dic zT%UVg-u5vy6Ou_`K=_d6N!}d0F@8g$C+9P{*XLa~28YF5o|iSxNI98HSI$*QOVA_u9C;rCwe>lX2-hBjn1W?rgFaczJzUYdt!j{kyVx9?X^P zwjo0s>0gj{hO|$YpXY|6(!cGbyXBmNbQfn^adGZjyYkP^BB$^O`LKTz*yYNf8j;Vf zn;X&bxOL;^jne7TY5Uv3r+E4O_UYq(oAPnm;@Xos0`BL}_xSl-!G{J%L6mR4GCaG^ zfcw;v&j`n;ybyg%h7~dT<_kYdFHk(|KwuD4|EL~DB#(oIh5~gd@InW#0Zu;~LO%)k z0tf#U&c>{E@b3V>*ui^&_d59Lu=gttj%N&t?>mWni7}+_z<+?g4B!Be1N0rpZ{lVk zR2j&Bf@%)YPsp$$M&E(wgy<)E^i$OFA^IsEy+pl)@@1eT6GbecW~y(6=rcWfsk$*l zXA8;zeFsht6=_a}h*$zoocRsp45Ttq#1imu^jwHusm??dvijLq$JP7Q=Pk~ABOZD? zhWQt&ouT{-!Igmo^4EvxJbj*l1Uwoo2+=>NF17kN7Q}J#`9~qVCX*Sl1Wv2J8LA(j zUaNi*qSt!)&sBdFqMxhyeLj|-H62&y>$XXpV?Z39mhy59o#RP7^wgd9oUgWrLlD7w2xy}TwS7Gu=X2!*Jm;#mH_>p zQ2t9i`g-+|5Z%weQKdrkjb8p1^&g?~w|MkcH4vh=dh`zU^$@+oqj#xKh3H)#eVcku zsD8J3^sCgrhU~veRijH}{qfF;t8Vpqi*wwJtL!c{ro*@O^Dv( z<^Qaj9io3$eHj;$_AxoGKJW2=Ui~&yA3pt7^}`VTRxkhU>h2Kzc4gmvP*b%&&XO{a zz-i%aA%35Jmzor+|GP4o5lg7M)xJ>q?p9A@(94wXK9B!C^>~Qir{AymE%OZApNS%t zP!Fh;A^HOz{hMk=i2hBF{*d}jsJxshXCR?=DV`?G-eKkaX#G`*#b%yBQ z_2`eOaiRKr%%eY{eigF+36K7?`c8=cv`7De;u*dS{2&uWECJ7mOGET$Jo=B+)DZng z9{qXs>rnZg_vkOG$3pZMJ^Eht#Sne3NB@Po0#hEgp9cKsYqQ$+hX~-yaE!Wjtf6xb zLEo9*wm3^t1m|PF!aEMk-=y(L>R-{n3$SQUc=%5}eARg2HuvZvcDxpteN^~beJQT!3L3L*JFsPXRx zzBdj2m^#ziU#jU(s2|$;Gx*agZE+T>DE_(KJ`oZ2XK9L{sed#g#8R*3L)1L1$US= z14FJ27_MjdWwRC_zJoX#(bsJHGZuf|;(2IrBpjOn15@ye` zA&mvho@0H8qLF+8cnV=J!m@IlZ6=P8K;M^?Gxh5l)xIx7I4X&H%NAnIk1&Oh^;LGZ zssFO~VQt8C;1@9j&iXF6AO8UKor&hBrhY@CYBrV+xV&oWUt0VFCg0QtEdC)=&t;30 zszOoh z3ch80d=>!L@_`d(uQc;arlV>!AMGH1vBeQ6`sAEp({U*@pH9DEWPY8##`x+i!wY!R zkdQ)%s#9g_%=J$p)OsFK@V*Us2w4<-p-;o?3ys}V1^)RZKCsi5+4W{$WUAn-1iJ=h{nH=@x99HK%DI*o@45Z_+sLD zrap)_5HB+CGZUxj@yX_XC4L9-6BTB}2!Z!8gt9#re}*9{{bh^qV>ku>P=DmlVK~+F z*Tg3iPr@!s*FIL!_|{pR{WyK4US;uahO_YAv&FgR6G!8@)8acA&VhXv?_-GmWw*uq z8CEFujKv2SqEcS6_#i_x`a>4~14Hx|`Ei7>cRWM%7sVEz!VvvMsl~N#)oRqM#W`P$ zOaXuG_l39vUnv!+=t67zJlR;Tpx?`eV2F> z?mLUOGQ@q?ZSn04ao_b?{5FQT|8`jXUWT}zc3ZrkA?~MVEIz=n6W7P$gA8$h@m+mh zk0FM*&;DR>K5W8tOpRvS_9aUY&z@hXPh@JVd(I)>Na{;+rh z!|h77TD*hd^=O|K?`DYm^CpY;GQ@p)r^R5Hp}FPq=1#gdY~PAkTn?9KN!w_%XcZrB zZ0TCnR@>UR>B6?Ime!C8?OpDOToKODbe`(<__~wh&owBOA&93z%ND%86Hzu(7b~mR zb~d(c+1%2V@za{I5DwQyl0DM`Iose*Zeunn9x;oI)gD{O5}%k&hPkd;46#=|L-nKt z^?4*mw7S?}I)a;6Q#;KO&S6JTA}nEzF5cSF+PtkkLP8`pLdwdmtz9j3o$VW%x6t8o zgruw-5z@5X5i-2=h@2~ypC6?>oE(u)OV%w~8e`TQAk2_WR+vjSvf#RBXw2=t@)mIq z1-al^)%fp~8!$+S>Q>C9UsglTX$}Njp+c#WV+u3}Xa?LHoybz1rwcA#;wO*;OS=gs==$dBb@-C1_ zT|FwPS-G-EUAyhbc1Cbyk+%AX(jqxLX~8vGyN$hbxDK=Nu09H0Q=n0c*6h;2M{m*E zU*R@Ghs$TitYdZF6JS*3M?*%QjMrSYGeV-rxb8Uc?Wd$E`ZU8SVi_ z(mgwU?NLIkVTZSby<1mfmvyV{Y0KeChiPq(E zt#013HOkX>wl?8S8kV$S6j-^nt9fO6Q+8!uCOa1oXA7>%XqY34?PW8A+vrqyy!G|^ zxLp0#)~1%rH@7#b@O$oC;fy-sMfYqKW|}!C@PW_kpr~OQFAJ_)#z(p&9MOY#Mvin{ zhtoBJC!#jB#1V{P!$**_$#HM7!x?7pqJSlvJfAOYmQVGhn38Qi@p$ z?WVapd4YDfJzxK?)c>R(J*8ij2cF$e0<%*WB4e7b~vO#O} zT-_#uv2L!;wm`e`p0EE`8n@p1f5y=_Jc846_X6$Ld%p4Rt^a3n{k=f@_?~Y(ee3@j zH{eZk%XNzWw?I4np0EE`>i=)YCHU6ydOHl8ECvek9HMfPVCFd)F>L+mU!Em#@6-is z)o8H(j`i6dCXlaz5ewLY)36zPRAUjVGN|4xPa^(H{6JEamyh2nAkZE7<+;tKlZPOB z&-3IZOHF>t!{fL>-uqzy%Od5t6LGN#(I8%K_yWBJ_X|W^ z`}ROy5-hCe6Yvvx-!<|A`?%*x`^ZBeAK`C2dHWpu-UGVG`v&UEweJxSx+%bd*!MN? zx%S}|o4~%4z$@}@F!BQX7UJfiedHmKk8qtQukiFtyLvC^BJWJkzADJ;rT`0K-|3#b zV#rH^hxK;~ej+dC+1GFFBM(9B`%ka_7CQEwYWY~MyTRwy-yXAoAJ} zcja|E^6+RakhjJ3L&0^s6Y^fBAPXX|-Rp;XAg>TSzr-(vpV)W4kr&w44dZAZc?cr! zTuYXe?Au`E1@`g#^wdKhg4kE@$=l}0TWk54kBbb~ zzDFSMPnd2&?E3=*yXEb6>0m9eKy2g53J+hdho40#bhy5pnBp z0P+gK^h^9M!B6aa6~f&5J7n!64?*nvHJDs^gN}U-mXFu>?~S}nn?t`D)&73y$=m11 zTkpvGx{(*uUq0kf4|xb;-(Pt0h8%fKmXG;z(B8lr*i;C4Y@Y&Bf4?sX*9*sY=HF-; zMejlIx%G0$(Ypz}n3cZh8A5?`A8Df#@v-pDQmP@{*uaUMqegZ;X)_*jI;sljS21LF`L-@=6{1+AJUQ zy^5b}-#W;PvhUa6bL~qx_H{V&_857Aefz9^|ma6i2Uu`n$o%3+!t^B~uT12x8xLp1gj?zE4>`=6gTZ8?Jq6$eTk!7R0`@ zz~|bx$C1|!Ub(&#jl96V+pK-$A&7nBJb43-ylX5U?YqIVkMDR@Qji6)?>bN3UPs<` z@QQsO^Xwb2_K}Am_I<>YH|WT_-ty7D3I0mjur*@%t=(QZK*p+7 zBkvZ=NBhpfKeztYLY~+}c@nQMe1YC|R`0E30*KzZ;B)J_)X{sJ<)hw*z3bKhc^wpF zLG<={*DVEkN${|qZ^uvS$>$osnGqkUtc)V1#s$dfvwJc+*vX7B}icU!&plL;Vt-vFOmj($h)H!L6Z?lS#- z&<{P8Meko4zCiCDtM>sa1&H3Sd;RksNAF)*KI+|K$`R-t$fCE!@CABbuzJ5qr2x^} z3_iEK1CHK4%SXMx^ve5E7QO%Am3PqUeTYf{qW8yMdG|Vczh(KT_b*I2g7WUmqW8;& zFDUP8R_`t<1&H1+g3m4Qpre=bC-PD6&%orit6|8Sf^-3CR|AGG&|5g!CHFqxW&k$9g_(d|2;J$SXy(2@7FBkyybeSGjn zJ>(&XeK&aWiXC}>XZe_Ky=PxO78u#{=jmI-nE|Iq@(wT;FWq_n;X7v zQy?!DXw9_Ka}8f`Jyuw~&v<%k!RKC&Qb+Hzj^1gW-nCiu7JGWPTfIN>^iKBlrX0Nk zj^6WO9NJaT4sL?HsCK&8@CD_4*y?@W(^~~Tx4a7-y+3yJ-eJ~_f!^I#o)s7L2mIcs z+wPyTd@p)>Zv>yKx60A`6Gv|gF0@5Cz??HlZS8~1Y>KU z!(fJQogfH>Z>hcCgwz9hduWsei7xW)qdJtg9}0d6zF*)+KHk5d#LX&o2~^eL;dLL< zsP9(%$j9>HdoE|4mCV4AzB4p$;lhQ6`^evO>E(sN4sxXqO7Wg*ObzY2y6+MF6@#g@ zC)7?H)prcy&&86lzM;^U4B+7k>F@n^OwIb=p4wR50AJSdl^mm%Hxsq^0!NkV{HNOGhs4) zHeR2&E@yi#yf*q{p^GQMe>i+L=&t;0wEVD7$iwBQd>?rJMj*=fTORs|41^H$Pxt~@ zD2cPI4AA%69~}9a(^!Tlp^j7k9-<$Y$&6S6J?RwWRNtIS!rHEF#eY@r)lj(@)ZOgaGNM17{M| z(s#^<5Fwt#kG^BZh4ACl_mECHuYFOxP`|rO{2Gl5z!#v}=7L^;F{_3l#t`o9PUXQWfa_aB;~2wqhyi07A^{)9^0mMVaQNus45yL{ z`E8?|jXiaZ!!TY6zDv&b9EVK{Eq)F|3^KfHNngPb`Z)FxznCHPrY+ve5PG*+{3?df zcZbFAWC*=GE&c#QR*d=fn?B2$?L}63u{1b)e5BVUSFfpDI3MquM7%gSk`!?)Ieexc zf~uREI`KZ^isrUWU1_|V;=dF-nhezAyy3^f9L<|wQuvXt(S*+dD~%r2`z;X3m(lnt z1>exQuwza8*3J!~H)BFa-4D;N^+&xk($u_u>!$jRosII|M?}ptGsN3BHS`;KVp`;h zd8by)+Z0EY#i}_v4FUJa*E8yyw?(|6fz#IJ5IN6Xo3r4InRD5U>EqKW+zX?GALBlC zyZi09FUL6v?3V}(`Lo?b=s5=IGAG>_!N-190O~ZX$A3-5q*j;-3JEBL3gM@^qv7eSMP2|FO~&?-ds=b z5NJs)$@~+&Z@@VG1$yaUiF#%97QO$DbXV_Fj$RH0QeM_8Sc7^l1~MDCfarY$39h_n z9C_^0Mc&njLquR7&+^bd@({$nPa^Khd%=;%^`6M1KPdbK_N@SN4R8Um?;fPP@?L^G z>SVj(%tYk18hL?z^fN;H$U_kO(w@B69Q(Lz6nS5T0bmX6+Y2NKTtMu*#qb4s>Boe6 zi!Gz*{T%q*atu3qPXe##ZT0l>hDcgj41j7_Z}jXh4e6M)&_JEIljDVEmU%=;< zgJ+bx!9=@D@RM@v2B)DSk5E2P4=^Z zU?1pM+w6*->FH`3-M{5v^V{b~oUGDL81nc3YWutZwvDoV&X3%uoR>_R@1&dm<*C$y z1q+hNV}0ja{T})iS2S&kScN!k>qt@dYku3j(8=^pX`3ry^C;Wq!gA?25e9u{*0xzW z>b{e6Ucj-wv%a;pzOiY;+i97LP?3JST%)Vk{ClUg%kyCF=-TDkDKxhg+01@L9n!F;l@Yo(EDvXD7Joux|F*kLzv>)p)%{f)4p0n;@R+OhA_b`w3mw()~ zPfNwI{u1qR^!;UdMdbW4Yr7QgBhN37t$m#NWot)Q%jUPyVd9#;>zP6U^kaKQ&Y0eD>9Kuw++U-gYgSYoYnQ07|L(PU#}%D#XQuh?d;U{V8M$Yabu2&D zU%sWi%+3wR*5*goUoMz`Y#jgZ?=L&s-qs2BcVU0I@aWb)$NI~+)?aoV>o1S0znqtf zd?yW^X!JA5V|$rzsaNSGUv^UoMUEfo5%Xhx7Id0-p(ofnj&wk#% zTaI_(GxN%dqZ`kU^_g#}&)m9Y{jojvqj~mISsA%!l%>zCoOhNzE_dW-lBMIYN#OWA zn1#2V7a#ob1y3AUAKURpEVgRs&6IlemcsK76vqDkfQl_^P|2Q#++==(@ueXL$sM7yIgK@b^0upR_2Z{S7DJZ#b5Y z4ULbDKmGU5#nLbCk4-Nb9&9x9lHrC6P6DS&mZ$HoiT~8-QV(`KTG`O?C@z&U7*O@2LrjAFS->+VdLFd#Hz5t!S8_F5_bZ&alg%jel@?Kq%iyRG1-IX~0 z1;p!Or_UVjo|*r6?(e#1J_8(Sh1J8|<%kzDenaAo7hgIwzEH03`LE>6I=!l5(WFJy zLy7oFwa*+HpL}#*M{tGN)_WdYikABneq+CqOU4YM-fK|jaaGb=)AM+&1h{T3Yz<@L1&iYiaOpZUMpd0$9C)~< zjqgMs&~QH+Kq+E{0cL#k*G$L>`FSS4_~0Y!WBAof2>d#SXgh>wM?7OwUIO*+H~cc)F{8ukGYOSLS887lOj)jCqx&|6GmPF-tis|(djKO1N001 z%@F-KbsxwyX$OAs;Oq53014pV2=PzS-;XCh%NEyPOed#-1gQ6g_~H22fdszpz9U4Z z*TW1XAdfy5GXRIj4kX~|ZyJ`ZJ{WB z+z7wY4HRa9{Ig&Wlh_7|;wPw2S)AoBiW~cVKh9-nboAqvvW;&xE))HSl$~t+AEprg zE%2$E-G*TskN zrIl5U@h4ojVnuaZ)0!(ch4$tU0Ifh}d-$+{2-r21E6+0pi zLmw%L{;kV5Z&}*{hc>>08(n{{%jK18malGX+tj?aaeZsEs$N!82bb0x3>NZ+v$dDQ!-q0d0ZdG8Y{O%VKNA3~S{CZDg=ko12MU1azIf3O#W z3e|xvB9Grxas8;C1811zn~5KJ_#=Kcey-jo;I3YgS7!JEy*B}8ekqsmoq;r0?_x(U z{c(z3OkqNL+2@VNPe981uSjs^t$+}Ac`OIhMcy97QI5dA9l&WHc?e?PQ;56rE_UqW z5-5;o>NzOiPS7}>2n6!HdTxR|_QSM~KAlD0myEo?KKdu7eZJr4TRnMKIrdF-4tXi0(LQ`;F|dz)K12le(U&gmBM(93r4e`KJ?z*ges`HK ziTtj8#lShf3W&TZNO$G!cI0tpA@%of5a!xUQNl<;deF8ARST&%OtM zbG#Q2d0n1;&p7fpGZ1-8jl7`#mZ5WCJ;>}wun>vfO%k$_XiJ7JGrW$0pAi@{X=|lY1(l2G}4Rvk-stK?7u*U zUKhsFW5*<37&vrW;n;%MAh5CAhqx9y1rxd75?_6&r0~h#ULF6%zW7jCe9U;PC$at< zj-58R{6KeO|A9MV(*~bRe-C>BiNyDQ8!w8V5q~`v&l^abk@L84B)BToxt>fv_{M?P zpZsm!v?tRSEPC>{)$8Na6WB>%D)mz1q=s(pg(Uiao51dYN)%sQ@_RK@=-95tet?%r zLoA-i$s3c;%d8mRaeYix9hXquCu6jkKVDVUOjO<5(Q28e2wz*7F|5=Ath$!%i>cO^ z;_viz?^=}G9Sa}UwG#dpM_U$%T4Po^^vvwQHNK+tCbU+CaL6cMf& zXCR~q+R8QBmn}|Pi?FzmdzWL)B&@-t58*8_2_KyqMo8d2I0=i5pKHvHIs6C>fNL%+ zqf{9NX6j2J`~q>1ZzqoMF5(zOzed~+rn8}hV=&h=Qy4-{sm13oq!IoaBVtWq=EmlO zG@O&Vt|^-uyBgySA%8NL%(O$p$je3GIOX%P z{Rv2aKN$(&3&zAA;AjegEh3L?&mBuHhJECdc?|i8--@5Bw-@-s_z8%-&m+N=*93WN z|CGnFiM$rXUHkYx5cNp;MP4(~TzR)S_K{!Y$^Hn)8tD67WH3SEuOZHINIlg7VI2sN zM)(PSE?)x>>Jt#Yek8bjoYS(r0-_f~wB{4q9pIDxfV`B!--R|rpyB^8(E&lrkcP5$ z2#I`AbBb?)LGqAyAqwucEwS&Lpt<#YCxj=F#_Q(JkxzjzsXLGqzu_^2kUE&3@(S^T z%jEinbKA@0*m>|?Bc8@YouQmpvA`Y(I`W)i4i!1iY2E|veY>vjOV<{c@L2*zS$rr1 zW2}1mKu!#EhG}X>_r4PqVwdI5j9rWHg4pyWjd?SxHx!nr*UuT>zdy0)>BjCu$*TVS z1&g~6rBdC87N)wV-Gp4%HkmIM@_#(pe;`%$?0%ISPsV#colNxRB%j@%lS7Tv*P@?g zoMivO27J76d@|M>Mb8Jl7hgy$%0e$pK5?KQ`HQpAlb{bFKT6XPt)VLU#KB}C zIj+sZk=NJvDC!Ep>o>IP?!KH_g%X{r;yZIvO}aLdX;s2{?5WxK9CTI1dshur)t%HE z-H{n6tZT|&RS&BR_)KQpX)(rbiG4YiRL7fK$KwD|GDM>AzA(Ipbg zChA(DMF~?sn<=XZPe%%arz7^BTLk~i?QP9%UGGa)cWzD+ZE0=pOm1xNOfK2HzPYKX zxhc6|Zu!FG+V=L=_az%UH*aXgURUy?^P4L-Y-miSK86i1nD~F^`;+fOqi~)h)J!Nf zeFE!@FpQt~eM)v~!FPzrbFSvezd5$u?KMcjm_lX?QS-N)P!{RgO$L5D@=Ygy=4)9( zAE(zkA|GEG%R~|5w;$hw{1m}*a{e~p$YUSI@AVMU_)UsWRL^V7{3G3+UlOnJ@~=S} zlUPqh_*Nsw1_AOvB?v;|zq52+@k!WR{)I<(vTOcFodo8;6+b4i&WkXgybqxO>AM6$ zNc?^;e?HO*uvd>MrJipVA>@3M`)dVAT+a~m%THPQHJ0APbnK1aZ0UMFihTE2`c6y# zYfFC&A?LH-v-CZd{`Z#tb4&k~rSG%!f39Z_-j-^*v zI>hLCHOt5HrWm3^7BEEqUWOR-Xg@>FtINRr0Kyc)=b4UyaW6yg{|m#(N^x$%Z(tHQ z|DJ=e02?k^F2Zw&V^Us=aH`!D;WHC|p1u%t&fCe)c{=N#cmqT5D}Fuj{EL<^;+A|} zXG?o$OV`K;1`(5a=Br-3s6O-^%HR`;BPiY;w3B;rbHpbqZGKB5_tLuMtLhzm@yco! z)nqM5LhH$dCSXt89+1^>dtg)>L9k8xInrrs|7o{89+L~KO zJc^)Is~0W8cOC1RJ6k%^i&mUxGMJ@`yA+B3LIefq>tsLJxP0{mnQLbrzc8u3Uia_y zo14-7cUE$tQK9Cp-?C+H8gk2R6izSsAqxG`#iRZ5qEcT*+jo1=BqpR|<7i73K-O>~ z{xi;IMyNDF@SpQL!Xz;HeC$UBMD%e;bLW-Ya+Tu!Og*%R^3b$p4jHUhI*^a)VzcPw zJ?6@5fT850JcthDtwh|lZyONy!vbR8awNF&(vY_fX_Ut~yV!R+;t&zo$9XUHl7}Gn z%|zUl*YDWJbdmQt#9jNkAdmgFfY^5f5?pzEATNnD+J`PKkhckO*S>yhA9)C3-v-28 zdHWpu(3J)9{u#pD`scUm(iCJta~DTWgc2 zm>K-Eft+qQzYw#b73~&0(3B#wy6T# zIK?(x%n)-j&Up&Zd0oX2mAjoGI;b9o$aE9KiFU5W0s-9fDU`>#60aNgJ{Ma29EMar zioH+0Etqa>tzX~X*x6Lyf>R65CS?>AQ;_haM$ci8y88U3X1aoSW^UunQKGg=!}AvZ zummR!e|dRLDq_zxVnTDYGnSQTEa+MT;6CCNPMee{L;i57HDsHw@Vfha zci21(H4B<)evHslo%7x%_>+31tN&N7q>xS}p zEjBc^)t9F-8J3E6!g6s=akJ%b0?z%gClLzp-YRzF5tschmY-w3zyIX0>wEJuCxQ88KZ|t~ zwV&nBX?XvaVeWuGmBPOT2swwSLO2z32mn?=>?C*qPb&Pz{VyKsSH6XAFG`FyyO8n1l%+6BOH1i~qZ;{1ZQS+Q#Le!z$Jti@M(S8-8Y`4_Id5YVHsqP;91c>W-L7sgcgU+TF zX$8PJP8R^b$l@1Ue51u%Eq=Mh*`JdCdW*9h#BaAa^-cv&;Jkx%!ubI2Z|+IF<#|A8 z6M@fpS_$kg-9D-kgbt*Q$B*_%A9Xt7kQa=RF9B!YB{q|f;EzFa_L}l? z@e_HxwzN;`=w-xdivVf-U1~!~Kb?sV2>MZ^!4{gXfqYSY_oqRXJY?kDUTh#P<@i&? z-FkTd^-_p5mV@(VDaTh3m%2n$Jq&r>2&qHL%Y6KNOMQ7ou%JHDdb)f;YSjDO=NO|y zefOFBhgN;2Po2h9@3Z@JuizPw7|+$7Cnrp>jvW`{X%l_QWZdt%o2!S|o8uJ9v>0PL zebIrT_eJ&l-S(6ULVHRjU$3CSU#^Do^%}ZVpYq`e5bSz4s%iM&!qH$|?XrW3n3{(F z`NUTZFRP0Gb-Xt*qqMdhyXA?cOnvrH{*F~cu>za+_1rHpwfew0Dt`YhPpktc@#P1G z3W-yTNg0?z2I)L9O zIP9+jK8EQz+L|#Kg@!(l%WK-yJMbLK3>t5t6^(ZBgc&!-J{!L=aYIf|?q~9@A9G#) z_OUe+s)R>Ep5YaU8jJdbs6*)`Od`jk_an-CggQAEaqJM_{jy9Dgv4d+xC3#HK|5{u z7(bUrR_l6`2?y*14I6B2{dFIf98Yg^YK~> zNS|4b1h=2ff!;LI{PAZp(vUqEe|7+g8h_YUTzRdKM?Qc2;dF!Mr0^r`1QIp=Yy*va z0>5z)Bno;F;!xG$@kk4@jc zZ=%Y|Q7e5Z(t5*$8%P*OQ z`Nk&vs@qYbJk(k;|I}Gkr*)UK<0|19fcB?yJg?i5Vm@2QEo?CJrqbH8wcZ_<(uP6( z-&j&r3+dHJeVo?VKIk1d_h6qc!0}(631mxm=PHNL!7ZLJ<>uH8@t(wIa<0$4E^qso znh87D?{RG*za^iDh9yc} zgK#QB0)4K)6cxwhiv0)ool+L(_2z!mGK=%N^7&MU#k&|Hf0lhJeL$6ax0r)f)OT%j z&Z#1$d_+n`edh=srf@OgI6BF4Zh3h{wsXrPC=t)SEKlTfuP`lGs*LvBGPCQ)V9c4> zfQu*w)=^-ta2}e;I?7A-3Sja@JxfDAN%o$l(HKz8$sqVRS=_RzrK_>EwxzYpo_}_! z)oqQf?VBv|@Q>jrc$9~tqd%ca0dMV4^gP?b*xuYj(rj&Sh6dg@F5ni@a0{4xK8`g4P^aN@U~<<$JZqW;Wh#EOhw^yaVNF4K!P@Xn zn=UqsUamh~dFwD#Ge70YT8a2ajJ%*6_aZIIK0dc`j6}#!>Q>BBL*FnFvED@~C4pd>AT6#m8}b zH1e9j$LqnmC9u3vdmaA?Ch`gFmkP28Lc13ckU0ElAm2Jc5DMQJs6UC5yciX6lfx(V zavJ#D>$VStssbO|0mowUv7EKw!(RXcAS97M9nzi)5$|l?+V6Pnx zQBz5R`Cpz&Em(ka<`oOd@t+W!T?S|`qM8)wkFm>gUuo*JS{?=SRm>f{hzdS9Uz zsrN%aO<*~=4on-8{?B&*cb3j_@f_JlJ-Xd42>5^M(I4{g8$A4z9zM^*mwNa!9?o$_ zfcD-i2twkwdw79UAEehg^-tVAmq(oQ00H8B-;qhYmRzR_nf=Kmz1ji|MB+UE#y*B; z=-FntF48ivDAVgC3^r^#T;H)z;yNzLu*mou;d!@G;$WV`5bK{5Lv-ex2l4$z0@r)A zhwC0>RRvf#oy!pGp*DtC_YnAAqz=*FP%qaPvM!+>;?%=+$zqEyW61ugz8)YDv8#^~$uJnV3P(pY$fvNL_YpPeTt*E~c|AQm=I;}jMmU()i=gvIrkKB<5_mRGK z`N{=>I3VR=Y<@t?Ozn{?bM_5L<{d^L*=O>jcq<@ct-&$Ed0D}r-XQ>%^XcRJi(xdCiWEC-RaK# zDfiY4&=@zvWcD+B^TFivv0oE_cn#%Xa_0v0S=Ipx?@8K2KHLi86ET>>l85PHv&bv< z6XmgoCm-d1#mEcn`-4rFQ9$HzFT|C% z9R#tD=^`)3$P4P3IQta=k@tHffE4I01VVW-x(MGvq`7);a`du46us!?^mR+9Bx2~B zAWvivm-uYNK?>%a^jR4-=d40H`2-qW1c`$F3*z?DYgY2DlS~dD_l6`7$-9BnIecQ@ z¥xmpxiTglKGgsq*3|bv>Jqp2BRxw{Dk(fs&k2vQnPn}(EoWlik zPDnA}&p8iq0C47o<{vo)yq5a9Z>cc z0=#$rZ{oaSS9Y|pIT^pjC&RAFy zcv>|-M7I-o%aBl~>SqhWuYkKiANFsA@=tfkDBo%7l@R?jkA8;wc8Gq4M=w)%gy>}+ zeV+PEi0-cHSifhf%R}_Dy!`K1mxSo=_vjx|RU!I^Jo+M47NRfm=u6d%5PhjfKTrKG zL_g1?uTn3E=&L;X8pVCb46MmS5lg5Kt1pD;ANJ@URab}T?y8&l>s3pLUhn1Kpe_i} zH+b|->U|;lCXe2xxF5&yhh1)fKk!SmEdL-etFFE&FTul_Q`KT$mu;x7ump&B^fLng#^fRWlQ1-szf7NNCyhY*Ct!buK2QCqq3gN9 z?(CQXvV3QT=$p`^Wq@=7_hod*MhxKliaNBqX4}QpY&-nS=EHixY%5^uVvF11rL5Mh zA#jRFuOp@|wRA2p0Am?ELK(U_ogZO{ z&P^oJFR*lkn!ehk&*r8(plq$BBh>T@P5SJl3A56tSvnSHT0cUa|06d43`<8hsp$wq z^jVhvF-u3N>6h62rCI0=mTo(Pvh_AU!chJ>Hos4o{Bte6+2%*6^KZ2BQULNUuZW>RTJqP04Q;4Iz zm0J27hG<`W-b(s84AGvJS$qY4U@38ot z3~{}8TKoZqxW12Ad^bZ}&pj4@hT%dKD(#*I(TM)?ralTHv=E|?gt&}250YVwI2_`g za){b{tl7GywsC7~SK#a|is`~F@RD+5wq@}9a%8T>&Fi;rTG`%qSdG~ApWSY3)%|>e6SNGW8X8dx52*-nvyh zYlIbA`r%nTL&02rWO;{S87VKY4-aml6QC(Po7p@v-&)3U>1Q#;PE87>MM_I;Yb!wo_*>US=1~vPl9U^ z4%r>4&PK9$^6WFmNI_X>o&@v2Fv^ffikDk=&a2m@qKgtm)jeU`hS7bdO`g~V-%_Y= z>56dAf%mt{&*ou0{jYo>qxxTk{x(^;{(qKA<5Thr^clYeI$o|3^WUV;H|g{B!9V?9 z|EtjMQ_J;#<4JX%=FtD=sr1&y&aMiT4vr9-$A*}on9;NqthA+^& z7&!AwxkT?{NOSe}IC`-J5A^b!qN{fWXi<94Gkk&GI`C1iRJG`(za>|1ucH^si9l~R z;;!Cxz@zkDZukPd7Xzo>@%Rx$Zztle-a8zPQ&m`)yo*f-Xb zx5tr(*AW8yUd4^-+P4EVY0HQP_Wc@sZaoh`9_xhdhEEBomv%g6pgj;j(w+FKIVImXWvUmi?Z){ zPafY968p|@}#<0k%u7mE%4;!W70x<*#9lDe8j(u3kVUx{mcDHs187`FW)P5+g~B% zN&m7G+){s?MqbeVx~zTVA&7l#p1e}WzU7vW_MMjq+sA#UV1hamPPJ$cI<`&L>$=DX08H>f|(&!gHuj$GeC&pyr@X&-qAVjsSC8M3d(v5${; zL|&!o4}$vRes+|7DX%~1b?p1FBX5F{7hGRHU#5NJA&7nS)8f|OPRBkzJ`wxw@%k6; zt4G;)m)F1aIre?jk$07m7udJg+D9IO*tgA-x5u#$kEsIte&Ai-!7TPY?Oopi$G&<; z-rYuCVBc%jKJpO6zCZKi?Q`sFw0x}hze5Iy2(IsN7W`* zOFiTvh<&$v^78R)iG1w;nk^sk(~P{pzI@1wy1vsrd4-TC{mUjt-tWEon{4eP4?*lZ z=+$4TV_%EqqkU|PtiKd~1b&yA{kH&V{PDZV3Oa~yhRSI=Eau9#b@<~0_fsb_{KpBLe;K#V|H2|SL0paUMg3HG>9m^{q zHel%1d_ubed{J`?&eugYW&9r(acJD5L0LP1K-`IS2^>Y4fE9w)`gZub-WDF) zrwNl2x<0L<-a$CmZM?zVZ3OV$>m?yN@3IWgM^{ydj*V^y5_lu*F5qNgd3eV96-#Fu zo`gek->^6Xrv06Ve-JqHv)p_)JLTvj|G(iUKzu!ZWMN(K-Q_q!_nRH8W4^P@e%}3N z2iHmbX2&ds6YaamcJXw$cZyTs=h?tYhPZE5SiFuQJKIsZAL4t!(VtBnLGhlu^C`OJ zaorDjTzCaIc-1&_pvp}ZIp&ia%--15)!DLsYgh9Yb$FjW=3AoZlC&qMQF`wId&Kkm zKh~SKNi+f(t8f(*{h6+E+KxmS@+adWucHg5D>P>}eLl8n0k$*3ZTPw4>1!Y)k;ZmM zdnk|N9By6e4dxFVTbM33i{37zx$?$?fqaygi=W6_h`4KC1909m0%Bh!5?pzcA+H!| zl*hYUjO@`(gTQnyyskba~%7aF7o(n+O_Wy;M4FE5c^gm!PU!WMAR!ii|A$9 zT)mZ!Uf#B%_n&QkkTtxF|Fl^^YX!$Ig%H~)7Z@>VZ9WEcQu>f@u z>@!q@;Qw|ITt2bSe}>BMtob1oMaS(9SPnnD2I7jqixXVplg@9r_+d_XRPI`$OGz{2E5Q@0~uD zvyKHS5W!e3Xb?6AF+I_sdZuSEi3wcI8Hn<_Qa;C40{7B+KXWXa!jRWulw(jZ z{&=0g|5Zpmez@KgGH0^*HOtLgIwCsuqjapj6=usli>T^DL2qQl0?SQc$lsCr@2GVh z>rKEkS#v)@UeGV6!N4mgw($NT@cO#_57!&yV?RY6{)qeiN(a)S`jslAvm64uBw|CM zrGUd0iqSwmx4#g+wMdsZ8QBMvGGal>Q3u>D#}4onB8}y6`|nQzmpVdJzbnvykUDbl zqdexrxw>e7*;#x@RaTts`;dYZ1OB?Chliw`Jx_X=D%`cbkMG%6<7*m^KWHi9icq~7i9PX|tP8Kv! z1{p2?JJ2r|`*s1YHLUOFnh7AdwACJs^8^9BS`)dp?38q_Epaou@@j=X-=3?<1d)a2kgv>-&6*`m-Vs@xDA3p@uB+&v4? zxto@OgnEy9!?7PHnKDGg_%8b^A^Lkg`b<53v5oSYajf2J`Ky3W!n?g&bOQzgU_V;z z$RobW!>0ph7G7tri-$whJgT%Y2^g zq6ogUYpr~?g`)U-)B_&>L8MbA+Xmlt=6F$7WPLXyWIBC;&0&bfnzHmtgelOu4?y2w zi!B|2p6h5ixEySM^tG(>qv2LqK9-lhnDJVhrtAEWbFQT$&_2UxE`2O>h@p>Vv4?g{ zwKosnZM_6IeJOvO={&p$pbuo~VR{Y1ARWTy5>Fbt84~y|>@oC z@r4Xg$U2L!We7Xc7H?$;{o5_x!w`CRSo~gw(AQ`2hZ#a&7N5&}mE_32lJV+A{i?R+ zx~;8nl@`nzgAavqCm}nFw=p5iHI0XrHIke~j%$~@AEIB95oOt!vd9$WS><^QBh&=` zn^`TI`EVaL1ruJ%34aY9J2hUiXRBclH*ujY9%KxqN9VLICe8cvkF5e1=k$n__e%{?V z`)inhS0Vj0{HUJt&?TrFjJ#ki({0nmMA3VlCy(cnnV<4xZcqFa7y#Cw9PDdW<0l~Y zorH*MUnS𝔎`^MS*?xyl7zGOQ2B?c?e>ke_pi9vCmzj{F5nfVBgD-!G2jl?E8gR zUY=u0f{FIY`i*uxVdMq&O##kynO%r|zAw8w9sBtFoqWu94}K64*f#@6CvX9=?=B>` z^>;7iVJOh{apofOu0$Ln0{dhQDzh80Z>uNoVaL8nj=YPEyuiL45MGNk0kMzQ+_i7F zV;^TuV&CbAyY}q^!g`R|mDo4allP2cABO5cUKR4=FR*V2$THvpVjs^Zxc0r^*vFZh z*mr`F7t|l0-O)bs5X8Pop1hYG`%bca%r}G|SOfd2Aa53M0kQ8jB)Imy=E&pBQS5sH zamWkoOI!P7b}9Bf>d6~+RlpA zEsb=3kADM9_h;OXp<_EzUDsHoJNu%mc3yMu;0dmyKvv}R9Xk$pDH zwYi$UYH0lURl~omz@CD_Ud24@RXo|hf6Tl^`b$mGdkg;F1Vq0jIoZGQW%ez&SJ6H| zd(A#V)zE$2u@TRNWw*HMKx-|Y3s-Zu0;~Bv>?~AqXW=J@2FI-$isSoVG4*}KiQ|$1 zBX!kqf5Q~`?>-e?zLULE?&o(dpFPyoJym~y5_>hd*nhEK#ljc4#^TFZas6eiwEL|q z`(><+59qIa<=HP|;rm(n`YT`ff>zF#@RhGC%5<$7?tcdN%o+0r<1^wr|Mmt z+}X9jyOv=t?+Ldn#?p~3fZZ@eEN;^U^=FQpj|ALLVV6uxFAC1QEFvodRjyK}>o z@b|U~ckydmnR=h%)O+#ch1k83dd4$!)Uo;MXusZp+R;XNgZlr>WM=<}&)Zo7@{ZR& z(Pt%P$B2zn-+%AGy_Lx{-U8Q~^87tp`V3)4$mcfMzN_WtXTM_iY@FOC`d`v<0gc)t z>2f=t(9Dzl;TY8(qRTAG$mSl&B_X=ZVuU_Xtqjp+79sSL)#b2{CbDk0hr#iP(2XCz zr!_>x0{g*TPI-u@Lixw24~Ozk)_!xCg>}h2iVryUF#nG|c{h5vjEkHT@OxRD4+$`T znMDl!MAJ@f8tLN8ib=#D!;d05@Z+Aya|i`U|D_-ZiJ$1%OO)TS(t8RBxfekH=v>oJ zqGaZYN zXBdL-1=2Ce;e4BWCc~EgdrKdWLQ}5(4i)%$=8AIp{tNxDe}W+=J^=2Cusrm?&UV2) zki|A!Z_`^5274lyC_#kYqu{)N&!J z4tarnPa)26 zMnLM1>v31!6v*pE8q4eM4O{@+wU6H;rd}CU#lDqDbLBnY*yrvIJYwVp_SHdN2hs$@ zzK4i_l=dwFExf94j~jyPHUW0yFM!t|Z_w(H_E!k%{||E( BD0Tn< literal 0 HcmV?d00001 diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvoptx b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvoptx index 68644d2bb9..18123769f3 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvoptx +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvoptx @@ -1730,6 +1730,161 @@ mtb4fap-v1D3 0x4 ARM-ADS + + 12000000 + + 1 + 1 + 0 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\v6-lst\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 0 + + 18 + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 1 + 1 + 0 + 0 + 1 + 0 + 0 + 0 + + + + + + + + + + + BIN\UL2CM3.DLL + + + + 0 + UL2CM3 + UL2CM3(-S0 -C0 -P0 ) -FN1 -FC8000 -FD20000000 -FF0STM32L4xx_256 -FL040000 -FS08000000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM) + + + + + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + 0 + 0 + 0 + + + + + + + + + + 1 + 0 + 0 + 2 + 10000000 + + + + + + strain2c-v1B0 + 0x4 + ARM-ADS 12000000 @@ -9713,6 +9868,170 @@
+ + board-strain2c-v1B0 + 0 + 0 + 0 + 0 + + 20 + 641 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\adc.c + adc.c + 0 + 0 + + + 20 + 642 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + board_strain2c_v1B0.c + 0 + 0 + + + 20 + 643 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\can.c + can.c + 0 + 0 + + + 20 + 644 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\dma.c + dma.c + 0 + 0 + + + 20 + 645 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\gpio.c + gpio.c + 0 + 0 + + + 20 + 646 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\i2c.c + i2c.c + 0 + 0 + + + 20 + 647 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\removed.main.c + removed.main.c + 0 + 0 + + + 20 + 648 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + removed.stm32l4xx_it.c + 0 + 0 + + + 20 + 649 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + removed.system_stm32l4xx.c + 0 + 0 + + + 20 + 650 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\rng.c + rng.c + 0 + 0 + + + 20 + 651 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + stm32l4xx_hal_msp.c + 0 + 0 + + + 20 + 652 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\tim.c + tim.c + 0 + 0 + + + 20 + 653 + 1 + 0 + 0 + 0 + ..\src\board\strain2c\v1B0\src\usart.c + usart.c + 0 + 0 + + + ::CMSIS 0 diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvprojx b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvprojx index 51acf865e1..93c7359bbc 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvprojx +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/proj/stm32hal.l4.uvprojx @@ -4780,6 +4780,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -9628,6 +9698,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -14836,6 +14976,145 @@ + + board-strain2c-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -19684,6 +19963,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -24532,6 +24881,145 @@ + + board-strain2c-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -29380,6 +29868,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -34228,6 +34786,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -39298,6 +39926,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -44146,6 +44844,145 @@ + + board-strain2c-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -47738,54 +48575,5289 @@ - gpio.c + gpio.c + 1 + ..\src\board\nucleo64\v172\src\gpio.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\nucleo64\v172\src\stm32l4xx_hal_msp.c + + + usart.c + 1 + ..\src\board\nucleo64\v172\src\usart.c + + + board_nucleo64.c + 1 + ..\src\board\nucleo64\v172\src\board_nucleo64.c + + + + + board-nucleo64-v1D2 + + + board_nucleo64_v1D2.c + 1 + ..\src\board\nucleo64\v1D2\src\board_nucleo64_v1D2.c + + + gpio.c + 1 + ..\src\board\nucleo64\v1D2\src\gpio.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\nucleo64\v1D2\src\stm32l4xx_hal_msp.c + + + rng.c + 1 + ..\src\board\nucleo64\v1D2\src\rng.c + + + + + board-rfe-v183 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\rfe\v183\src\adc.c + + + can.c + 1 + ..\src\board\rfe\v183\src\can.c + + + dma.c + 1 + ..\src\board\rfe\v183\src\dma.c + + + gpio.c + 1 + ..\src\board\rfe\v183\src\gpio.c + + + i2c.c + 1 + ..\src\board\rfe\v183\src\i2c.c + + + rng.c + 1 + ..\src\board\rfe\v183\src\rng.c + + + spi.c + 1 + ..\src\board\rfe\v183\src\spi.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\rfe\v183\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\rfe\v183\src\tim.c + + + board_rfe.c + 1 + ..\src\board\rfe\v183\src\board_rfe.c + + + + + board-strain2-v172 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2\v172\src\adc.c + + + can.c + 1 + ..\src\board\strain2\v172\src\can.c + + + dma.c + 1 + ..\src\board\strain2\v172\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2\v172\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2\v172\src\i2c.c + + + rng.c + 1 + ..\src\board\strain2\v172\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2\v172\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2\v172\src\tim.c + + + usart.c + 1 + ..\src\board\strain2\v172\src\usart.c + + + board_strain2.c + 1 + ..\src\board\strain2\v172\src\board_strain2.c + + + + + board-strain2-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2\v190\src\adc.c + + + can.c + 1 + ..\src\board\strain2\v190\src\can.c + + + dma.c + 1 + ..\src\board\strain2\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2\v190\src\i2c.c + + + rng.c + 1 + ..\src\board\strain2\v190\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2\v190\src\tim.c + + + usart.c + 1 + ..\src\board\strain2\v190\src\usart.c + + + board_strain2_v190.c + 1 + ..\src\board\strain2\v190\src\board_strain2_v190.c + + + + + board-strain2-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2\v1B0\src\adc.c + + + board_strain2_v1B0.c + 1 + ..\src\board\strain2\v1B0\src\board_strain2_v1B0.c + + + can.c + 1 + ..\src\board\strain2\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2\v1B0\src\i2c.c + + + rng.c + 1 + ..\src\board\strain2\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2\v1B0\src\usart.c + + + + + board-psc-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + can.c + 1 + ..\src\board\psc\v190\src\can.c + + + dma.c + 1 + ..\src\board\psc\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\psc\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\psc\v190\src\i2c.c + + + rng.c + 1 + ..\src\board\psc\v190\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\psc\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\psc\v190\src\tim.c + + + board_psc_v190.c + 1 + ..\src\board\psc\v190\src\board_psc_v190.c + + + + + board-sg3-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\sg3\v190\src\adc.c + + + board_sg3_v190.c + 1 + ..\src\board\sg3\v190\src\board_sg3_v190.c + + + can.c + 1 + ..\src\board\sg3\v190\src\can.c + + + dma.c + 1 + ..\src\board\sg3\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\sg3\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\sg3\v190\src\i2c.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\sg3\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\sg3\v190\src\tim.c + + + + + board-mtb4-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\mtb4\v190\src\adc.c + + + board_mtb4_v190.c + 1 + ..\src\board\mtb4\v190\src\board_mtb4_v190.c + + + can.c + 1 + ..\src\board\mtb4\v190\src\can.c + + + dma.c + 1 + ..\src\board\mtb4\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\mtb4\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\mtb4\v190\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4\v190\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\mtb4\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\mtb4\v190\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4\v190\src\usart.c + + + + + board-mtb4-v172 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\mtb4\v172\src\adc.c + + + can.c + 1 + ..\src\board\mtb4\v172\src\can.c + + + dma.c + 1 + ..\src\board\mtb4\v172\src\dma.c + + + gpio.c + 1 + ..\src\board\mtb4\v172\src\gpio.c + + + i2c.c + 1 + ..\src\board\mtb4\v172\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4\v172\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\mtb4\v172\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\mtb4\v172\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4\v172\src\usart.c + + + board_mtb4.c + 1 + ..\src\board\mtb4\v172\src\board_mtb4.c + + + + + board-mtb4c-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + board_mtb4c_v190.c + 1 + ..\src\board\mtb4c\v190\src\board_mtb4c_v190.c + + + can.c + 1 + ..\src\board\mtb4c\v190\src\can.c + + + dma.c + 1 + ..\src\board\mtb4c\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\mtb4c\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\mtb4c\v190\src\i2c.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\mtb4c\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\mtb4c\v190\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4c\v190\src\usart.c + + + + + board-mtb4fap-v1D3 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + board_mtb4fap_v1D3.c + 1 + ..\src\board\mtb4fap\V1D3\src\board_mtb4fap_v1D3.c + + + adc.c + 1 + ..\src\board\mtb4fap\V1D3\src\adc.c + + + can.c + 1 + ..\src\board\mtb4fap\V1D3\src\can.c + + + dma.c + 1 + ..\src\board\mtb4fap\V1D3\src\dma.c + + + gpio.c + 1 + ..\src\board\mtb4fap\V1D3\src\gpio.c + + + i2c.c + 1 + ..\src\board\mtb4fap\V1D3\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4fap\V1D3\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\mtb4fap\V1D3\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\mtb4fap\V1D3\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4fap\V1D3\src\usart.c + + + + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + + + ::CMSIS + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + + + mtb4c-v190 + 0x4 + ARM-ADS + 6180000::V6.18::ARMCLANG + 1 + + + STM32L452RCIx + STMicroelectronics + Keil.STM32L4xx_DFP.2.6.1 + http://www.keil.com/pack/ + IRAM(0x20000000,0x00020000) IRAM2(0x10000000,0x00008000) IROM(0x08000000,0x00040000) CPUTYPE("Cortex-M4") FPU2 DSP CLOCK(12000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC8000 -FN1 -FF0STM32L4xx_256 -FS08000000 -FL040000 -FP0($$Device:STM32L452RCIx$CMSIS\Flash\STM32L4xx_256.FLM)) + 0 + $$Device:STM32L452RCIx$Drivers\CMSIS\Device\ST\STM32L4xx\Include\stm32l4xx.h + + + + + + + + + + $$Device:STM32L452RCIx$CMSIS\SVD\STM32L4x2.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\v6-obj\ + stm32hal_mtb4c_v190 + 0 + 1 + 0 + 0 + 1 + .\v6-lst\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 1 + 0 + cmd.exe /C copy .\v6-obj\stm32hal_mtb4c_v190.lib ..\lib\stm32hal.mtb4c.v190.lib + + 0 + 0 + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + 0 + + + SARMCM3.DLL + -REMAP -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + 1 + BIN\UL2CM3.DLL + "" () + + + + + 0 + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 2 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 0 + 3 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 1 + 0x8000000 + 0x40000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x40000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x20000 + + + 0 + 0x10000000 + 0x8000 + + + + + + 1 + 6 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 3 + 0 + 1 + 0 + 0 + 0 + 3 + 6 + 1 + 1 + 0 + 0 + 0 + + + USE_STM32HAL STM32HAL_BOARD_MTB4C STM32HAL_DRIVER_V190 + + ..\api;..\src\driver\stm32l4-v190\inc;..\src\board\mtb4c\v190\inc + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 4 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + --diag_suppress=L6329 + + + + + + + + stm32hal + + + stm32hal.c + 1 + ..\src\stm32hal\stm32hal.c + + + + + driver-stm32l4-v172 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v172\src\system_stm32l4xx.c + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_uart_ex.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v172\src\stm32l4xx_hal_wwdg.c + + + + + driver-stm32l4-v183 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dcmi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dcmi.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dfsdm_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dfsdm_ex.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_dma_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dma_ex.c + + + stm32l4xx_hal_dma2d.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dma2d.c + + + stm32l4xx_hal_dsi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_dsi.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gfxmmu.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_gfxmmu.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_hash.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_hash.c + + + stm32l4xx_hal_hash_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_hash_ex.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_ltdc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_ltdc.c + + + stm32l4xx_hal_ltdc_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_ltdc_ex.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_ospi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_ospi.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sai_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_sai_ex.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_sd_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_sd_ex.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_uart_ex.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_usart_ex.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_usart_ex.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_hal_wwdg.c + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v183\src\system_stm32l4xx.c + + + stm32l4xx_ll_usb.c + 1 + ..\src\driver\stm32l4-v183\src\stm32l4xx_ll_usb.c + + + + + driver-stm32l4-v190 + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dcmi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dcmi.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dfsdm_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dfsdm_ex.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_dma_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dma_ex.c + + + stm32l4xx_hal_dma2d.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dma2d.c + + + stm32l4xx_hal_dsi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_dsi.c + + + stm32l4xx_hal_exti.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_exti.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gfxmmu.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_gfxmmu.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_hash.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_hash.c + + + stm32l4xx_hal_hash_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_hash_ex.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_ltdc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_ltdc.c + + + stm32l4xx_hal_ltdc_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_ltdc_ex.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_ospi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_ospi.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sai_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_sai_ex.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_sd_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_sd_ex.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_uart_ex.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_usart_ex.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_usart_ex.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_hal_wwdg.c + + + stm32l4xx_ll_adc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_adc.c + + + stm32l4xx_ll_comp.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_comp.c + + + stm32l4xx_ll_crc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_crc.c + + + stm32l4xx_ll_crs.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_crs.c + + + stm32l4xx_ll_dac.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_dac.c + + + stm32l4xx_ll_dma.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_dma.c + + + stm32l4xx_ll_dma2d.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_dma2d.c + + + stm32l4xx_ll_exti.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_exti.c + + + stm32l4xx_ll_fmc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_fmc.c + + + stm32l4xx_ll_gpio.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_gpio.c + + + stm32l4xx_ll_i2c.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_i2c.c + + + stm32l4xx_ll_lptim.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_lptim.c + + + stm32l4xx_ll_lpuart.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_lpuart.c + + + stm32l4xx_ll_opamp.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_opamp.c + + + stm32l4xx_ll_pwr.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_pwr.c + + + stm32l4xx_ll_rcc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_rcc.c + + + stm32l4xx_ll_rng.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_rng.c + + + stm32l4xx_ll_rtc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_rtc.c + + + stm32l4xx_ll_sdmmc.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_sdmmc.c + + + stm32l4xx_ll_spi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_spi.c + + + stm32l4xx_ll_swpmi.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_swpmi.c + + + stm32l4xx_ll_tim.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_tim.c + + + stm32l4xx_ll_usart.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_usart.c + + + stm32l4xx_ll_usb.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_usb.c + + + stm32l4xx_ll_utils.c + 1 + ..\src\driver\stm32l4-v190\src\stm32l4xx_ll_utils.c + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v190\src\system_stm32l4xx.c + + + + + driver-stm32l4-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dcmi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dcmi.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dfsdm_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dfsdm_ex.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_dma_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dma_ex.c + + + stm32l4xx_hal_dma2d.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dma2d.c + + + stm32l4xx_hal_dsi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_dsi.c + + + stm32l4xx_hal_exti.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_exti.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gfxmmu.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_gfxmmu.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_hash.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_hash.c + + + stm32l4xx_hal_hash_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_hash_ex.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_ltdc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_ltdc.c + + + stm32l4xx_hal_ltdc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_ltdc_ex.c + + + stm32l4xx_hal_mmc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_mmc.c + + + stm32l4xx_hal_mmc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_mmc_ex.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_ospi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_ospi.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pka.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pka.c + + + stm32l4xx_hal_pssi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pssi.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_rng_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rng_ex.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sai_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_sai_ex.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_sd_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_sd_ex.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_uart_ex.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_usart_ex.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_usart_ex.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_hal_wwdg.c + + + stm32l4xx_ll_adc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_adc.c + + + stm32l4xx_ll_comp.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_comp.c + + + stm32l4xx_ll_crc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_crc.c + + + stm32l4xx_ll_crs.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_crs.c + + + stm32l4xx_ll_dac.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_dac.c + + + stm32l4xx_ll_dma.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_dma.c + + + stm32l4xx_ll_dma2d.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_dma2d.c + + + stm32l4xx_ll_exti.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_exti.c + + + stm32l4xx_ll_fmc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_fmc.c + + + stm32l4xx_ll_gpio.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_gpio.c + + + stm32l4xx_ll_i2c.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_i2c.c + + + stm32l4xx_ll_lptim.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_lptim.c + + + stm32l4xx_ll_lpuart.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_lpuart.c + + + stm32l4xx_ll_opamp.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_opamp.c + + + stm32l4xx_ll_pka.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_pka.c + + + stm32l4xx_ll_pwr.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_pwr.c + + + stm32l4xx_ll_rcc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_rcc.c + + + stm32l4xx_ll_rng.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_rng.c + + + stm32l4xx_ll_rtc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_rtc.c + + + stm32l4xx_ll_sdmmc.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_sdmmc.c + + + stm32l4xx_ll_spi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_spi.c + + + stm32l4xx_ll_swpmi.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_swpmi.c + + + stm32l4xx_ll_tim.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_tim.c + + + stm32l4xx_ll_usart.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_usart.c + + + stm32l4xx_ll_usb.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_usb.c + + + stm32l4xx_ll_utils.c + 1 + ..\src\driver\stm32l4-v1B0\src\stm32l4xx_ll_utils.c + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v1B0\src\system_stm32l4xx.c + + + + + driver-stm32l4-v1D2 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dcmi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dcmi.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dfsdm_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dfsdm_ex.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_dma_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dma_ex.c + + + stm32l4xx_hal_dma2d.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dma2d.c + + + stm32l4xx_hal_dsi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_dsi.c + + + stm32l4xx_hal_exti.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_exti.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gfxmmu.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_gfxmmu.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_hash.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_hash.c + + + stm32l4xx_hal_hash_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_hash_ex.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_ltdc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_ltdc.c + + + stm32l4xx_hal_ltdc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_ltdc_ex.c + + + stm32l4xx_hal_mmc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_mmc.c + + + stm32l4xx_hal_mmc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_mmc_ex.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_ospi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_ospi.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pka.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pka.c + + + stm32l4xx_hal_pssi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pssi.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_rng_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rng_ex.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sai_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_sai_ex.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_sd_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_sd_ex.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_smbus_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_smbus_ex.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_uart_ex.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_usart_ex.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_usart_ex.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_hal_wwdg.c + + + stm32l4xx_ll_adc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_adc.c + + + stm32l4xx_ll_comp.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_comp.c + + + stm32l4xx_ll_crc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_crc.c + + + stm32l4xx_ll_crs.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_crs.c + + + stm32l4xx_ll_dac.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_dac.c + + + stm32l4xx_ll_dma.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_dma.c + + + stm32l4xx_ll_dma2d.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_dma2d.c + + + stm32l4xx_ll_exti.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_exti.c + + + stm32l4xx_ll_fmc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_fmc.c + + + stm32l4xx_ll_gpio.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_gpio.c + + + stm32l4xx_ll_i2c.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_i2c.c + + + stm32l4xx_ll_lptim.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_lptim.c + + + stm32l4xx_ll_lpuart.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_lpuart.c + + + stm32l4xx_ll_opamp.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_opamp.c + + + stm32l4xx_ll_pka.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_pka.c + + + stm32l4xx_ll_pwr.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_pwr.c + + + stm32l4xx_ll_rcc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_rcc.c + + + stm32l4xx_ll_rng.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_rng.c + + + stm32l4xx_ll_rtc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_rtc.c + + + stm32l4xx_ll_sdmmc.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_sdmmc.c + + + stm32l4xx_ll_spi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_spi.c + + + stm32l4xx_ll_swpmi.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_swpmi.c + + + stm32l4xx_ll_tim.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_tim.c + + + stm32l4xx_ll_usart.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_usart.c + + + stm32l4xx_ll_usb.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_usb.c + + + stm32l4xx_ll_utils.c + 1 + ..\src\driver\stm32l4-v1D2\src\stm32l4xx_ll_utils.c + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v1D2\src\system_stm32l4xx.c + + + + + driver-stm32l4-v1D3 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + stm32l4xx_hal.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal.c + + + stm32l4xx_hal_adc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_adc.c + + + stm32l4xx_hal_adc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_adc_ex.c + + + stm32l4xx_hal_can.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_can.c + + + stm32l4xx_hal_cortex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_cortex.c + + + stm32l4xx_hal_dma.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dma.c + + + stm32l4xx_hal_dma_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dma_ex.c + + + stm32l4xx_hal_exti.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_exti.c + + + stm32l4xx_hal_flash.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_flash.c + + + stm32l4xx_hal_flash_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_flash_ex.c + + + stm32l4xx_hal_flash_ramfunc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_flash_ramfunc.c + + + stm32l4xx_hal_gpio.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_gpio.c + + + stm32l4xx_hal_i2c.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_i2c.c + + + stm32l4xx_hal_i2c_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_i2c_ex.c + + + stm32l4xx_hal_pwr.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pwr.c + + + stm32l4xx_hal_pwr_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pwr_ex.c + + + stm32l4xx_hal_rcc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rcc.c + + + stm32l4xx_hal_rcc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rcc_ex.c + + + stm32l4xx_hal_rng.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rng.c + + + stm32l4xx_hal_tim.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_tim.c + + + stm32l4xx_hal_tim_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_tim_ex.c + + + stm32l4xx_hal_uart.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_uart.c + + + stm32l4xx_hal_uart_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_uart_ex.c + + + system_stm32l4xx.c + 1 + ..\src\driver\stm32l4-v1D3\src\system_stm32l4xx.c + + + stm32l4xx_hal_comp.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_comp.c + + + stm32l4xx_hal_crc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_crc.c + + + stm32l4xx_hal_crc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_crc_ex.c + + + stm32l4xx_hal_cryp.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_cryp.c + + + stm32l4xx_hal_cryp_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_cryp_ex.c + + + stm32l4xx_hal_dac.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dac.c + + + stm32l4xx_hal_dac_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dac_ex.c + + + stm32l4xx_hal_dcmi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dcmi.c + + + stm32l4xx_hal_dfsdm.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dfsdm.c + + + stm32l4xx_hal_dfsdm_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dfsdm_ex.c + + + stm32l4xx_hal_dma2d.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dma2d.c + + + stm32l4xx_hal_dsi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_dsi.c + + + stm32l4xx_hal_firewall.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_firewall.c + + + stm32l4xx_hal_gfxmmu.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_gfxmmu.c + + + stm32l4xx_hal_hash.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_hash.c + + + stm32l4xx_hal_hash_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_hash_ex.c + + + stm32l4xx_hal_hcd.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_hcd.c + + + stm32l4xx_hal_irda.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_irda.c + + + stm32l4xx_hal_iwdg.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_iwdg.c + + + stm32l4xx_hal_lcd.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_lcd.c + + + stm32l4xx_hal_lptim.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_lptim.c + + + stm32l4xx_hal_ltdc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_ltdc.c + + + stm32l4xx_hal_ltdc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_ltdc_ex.c + + + stm32l4xx_hal_mmc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_mmc.c + + + stm32l4xx_hal_mmc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_mmc_ex.c + + + stm32l4xx_hal_nand.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_nand.c + + + stm32l4xx_hal_nor.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_nor.c + + + stm32l4xx_hal_opamp.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_opamp.c + + + stm32l4xx_hal_opamp_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_opamp_ex.c + + + stm32l4xx_hal_ospi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_ospi.c + + + stm32l4xx_hal_pcd.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pcd.c + + + stm32l4xx_hal_pcd_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pcd_ex.c + + + stm32l4xx_hal_pka.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pka.c + + + stm32l4xx_hal_pssi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_pssi.c + + + stm32l4xx_hal_qspi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_qspi.c + + + stm32l4xx_hal_rng_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rng_ex.c + + + stm32l4xx_hal_rtc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rtc.c + + + stm32l4xx_hal_rtc_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_rtc_ex.c + + + stm32l4xx_hal_sai.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_sai.c + + + stm32l4xx_hal_sai_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_sai_ex.c + + + stm32l4xx_hal_sd.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_sd.c + + + stm32l4xx_hal_sd_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_sd_ex.c + + + stm32l4xx_hal_smartcard.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_smartcard.c + + + stm32l4xx_hal_smartcard_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_smartcard_ex.c + + + stm32l4xx_hal_smbus.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_smbus.c + + + stm32l4xx_hal_smbus_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_smbus_ex.c + + + stm32l4xx_hal_spi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_spi.c + + + stm32l4xx_hal_spi_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_spi_ex.c + + + stm32l4xx_hal_sram.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_sram.c + + + stm32l4xx_hal_swpmi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_swpmi.c + + + stm32l4xx_hal_tsc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_tsc.c + + + stm32l4xx_hal_usart.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_usart.c + + + stm32l4xx_hal_usart_ex.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_usart_ex.c + + + stm32l4xx_hal_wwdg.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_hal_wwdg.c + + + stm32l4xx_ll_adc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_adc.c + + + stm32l4xx_ll_comp.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_comp.c + + + stm32l4xx_ll_crc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_crc.c + + + stm32l4xx_ll_crs.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_crs.c + + + stm32l4xx_ll_dac.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_dac.c + + + stm32l4xx_ll_dma.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_dma.c + + + stm32l4xx_ll_dma2d.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_dma2d.c + + + stm32l4xx_ll_exti.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_exti.c + + + stm32l4xx_ll_fmc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_fmc.c + + + stm32l4xx_ll_gpio.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_gpio.c + + + stm32l4xx_ll_i2c.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_i2c.c + + + stm32l4xx_ll_lptim.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_lptim.c + + + stm32l4xx_ll_lpuart.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_lpuart.c + + + stm32l4xx_ll_opamp.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_opamp.c + + + stm32l4xx_ll_pka.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_pka.c + + + stm32l4xx_ll_pwr.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_pwr.c + + + stm32l4xx_ll_rcc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_rcc.c + + + stm32l4xx_ll_rng.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_rng.c + + + stm32l4xx_ll_rtc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_rtc.c + + + stm32l4xx_ll_sdmmc.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_sdmmc.c + + + stm32l4xx_ll_spi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_spi.c + + + stm32l4xx_ll_swpmi.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_swpmi.c + + + stm32l4xx_ll_tim.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_tim.c + + + stm32l4xx_ll_usart.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_usart.c + + + stm32l4xx_ll_usb.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_usb.c + + + stm32l4xx_ll_utils.c + 1 + ..\src\driver\stm32l4-v1D3\src\stm32l4xx_ll_utils.c + + + + + board-nucleo64-v172 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + gpio.c + 1 + ..\src\board\nucleo64\v172\src\gpio.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\nucleo64\v172\src\stm32l4xx_hal_msp.c + + + usart.c + 1 + ..\src\board\nucleo64\v172\src\usart.c + + + board_nucleo64.c + 1 + ..\src\board\nucleo64\v172\src\board_nucleo64.c + + + + + board-nucleo64-v1D2 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + board_nucleo64_v1D2.c + 1 + ..\src\board\nucleo64\v1D2\src\board_nucleo64_v1D2.c + + + gpio.c + 1 + ..\src\board\nucleo64\v1D2\src\gpio.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\nucleo64\v1D2\src\stm32l4xx_hal_msp.c + + + rng.c + 1 + ..\src\board\nucleo64\v1D2\src\rng.c + + + + + board-rfe-v183 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\rfe\v183\src\adc.c + + + can.c + 1 + ..\src\board\rfe\v183\src\can.c + + + dma.c + 1 + ..\src\board\rfe\v183\src\dma.c + + + gpio.c + 1 + ..\src\board\rfe\v183\src\gpio.c + + + i2c.c + 1 + ..\src\board\rfe\v183\src\i2c.c + + + rng.c + 1 + ..\src\board\rfe\v183\src\rng.c + + + spi.c + 1 + ..\src\board\rfe\v183\src\spi.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\rfe\v183\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\rfe\v183\src\tim.c + + + board_rfe.c + 1 + ..\src\board\rfe\v183\src\board_rfe.c + + + + + board-strain2-v172 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c 1 - ..\src\board\nucleo64\v172\src\gpio.c + ..\src\board\strain2\v172\src\adc.c - stm32l4xx_hal_msp.c + can.c 1 - ..\src\board\nucleo64\v172\src\stm32l4xx_hal_msp.c + ..\src\board\strain2\v172\src\can.c - usart.c + dma.c 1 - ..\src\board\nucleo64\v172\src\usart.c + ..\src\board\strain2\v172\src\dma.c - board_nucleo64.c + gpio.c 1 - ..\src\board\nucleo64\v172\src\board_nucleo64.c + ..\src\board\strain2\v172\src\gpio.c - - - - board-nucleo64-v1D2 - - board_nucleo64_v1D2.c + i2c.c 1 - ..\src\board\nucleo64\v1D2\src\board_nucleo64_v1D2.c + ..\src\board\strain2\v172\src\i2c.c - gpio.c + rng.c 1 - ..\src\board\nucleo64\v1D2\src\gpio.c + ..\src\board\strain2\v172\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\nucleo64\v1D2\src\stm32l4xx_hal_msp.c + ..\src\board\strain2\v172\src\stm32l4xx_hal_msp.c - rng.c + tim.c 1 - ..\src\board\nucleo64\v1D2\src\rng.c + ..\src\board\strain2\v172\src\tim.c + + + usart.c + 1 + ..\src\board\strain2\v172\src\usart.c + + + board_strain2.c + 1 + ..\src\board\strain2\v172\src\board_strain2.c - board-rfe-v183 + board-strain2-v190 0 @@ -47859,57 +53931,57 @@ adc.c 1 - ..\src\board\rfe\v183\src\adc.c + ..\src\board\strain2\v190\src\adc.c can.c 1 - ..\src\board\rfe\v183\src\can.c + ..\src\board\strain2\v190\src\can.c dma.c 1 - ..\src\board\rfe\v183\src\dma.c + ..\src\board\strain2\v190\src\dma.c gpio.c 1 - ..\src\board\rfe\v183\src\gpio.c + ..\src\board\strain2\v190\src\gpio.c i2c.c 1 - ..\src\board\rfe\v183\src\i2c.c + ..\src\board\strain2\v190\src\i2c.c rng.c 1 - ..\src\board\rfe\v183\src\rng.c + ..\src\board\strain2\v190\src\rng.c - spi.c + stm32l4xx_hal_msp.c 1 - ..\src\board\rfe\v183\src\spi.c + ..\src\board\strain2\v190\src\stm32l4xx_hal_msp.c - stm32l4xx_hal_msp.c + tim.c 1 - ..\src\board\rfe\v183\src\stm32l4xx_hal_msp.c + ..\src\board\strain2\v190\src\tim.c - tim.c + usart.c 1 - ..\src\board\rfe\v183\src\tim.c + ..\src\board\strain2\v190\src\usart.c - board_rfe.c + board_strain2_v190.c 1 - ..\src\board\rfe\v183\src\board_rfe.c + ..\src\board\strain2\v190\src\board_strain2_v190.c - board-strain2-v172 + board-strain2-v1B0 0 @@ -47983,57 +54055,57 @@ adc.c 1 - ..\src\board\strain2\v172\src\adc.c + ..\src\board\strain2\v1B0\src\adc.c + + + board_strain2_v1B0.c + 1 + ..\src\board\strain2\v1B0\src\board_strain2_v1B0.c can.c 1 - ..\src\board\strain2\v172\src\can.c + ..\src\board\strain2\v1B0\src\can.c dma.c 1 - ..\src\board\strain2\v172\src\dma.c + ..\src\board\strain2\v1B0\src\dma.c gpio.c 1 - ..\src\board\strain2\v172\src\gpio.c + ..\src\board\strain2\v1B0\src\gpio.c i2c.c 1 - ..\src\board\strain2\v172\src\i2c.c + ..\src\board\strain2\v1B0\src\i2c.c rng.c 1 - ..\src\board\strain2\v172\src\rng.c + ..\src\board\strain2\v1B0\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\strain2\v172\src\stm32l4xx_hal_msp.c + ..\src\board\strain2\v1B0\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\strain2\v172\src\tim.c + ..\src\board\strain2\v1B0\src\tim.c usart.c 1 - ..\src\board\strain2\v172\src\usart.c - - - board_strain2.c - 1 - ..\src\board\strain2\v172\src\board_strain2.c + ..\src\board\strain2\v1B0\src\usart.c - board-strain2-v190 + board-psc-v190 0 @@ -48104,60 +54176,50 @@ - - adc.c - 1 - ..\src\board\strain2\v190\src\adc.c - can.c 1 - ..\src\board\strain2\v190\src\can.c + ..\src\board\psc\v190\src\can.c dma.c 1 - ..\src\board\strain2\v190\src\dma.c + ..\src\board\psc\v190\src\dma.c gpio.c 1 - ..\src\board\strain2\v190\src\gpio.c + ..\src\board\psc\v190\src\gpio.c i2c.c 1 - ..\src\board\strain2\v190\src\i2c.c + ..\src\board\psc\v190\src\i2c.c rng.c 1 - ..\src\board\strain2\v190\src\rng.c + ..\src\board\psc\v190\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\strain2\v190\src\stm32l4xx_hal_msp.c + ..\src\board\psc\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\strain2\v190\src\tim.c - - - usart.c - 1 - ..\src\board\strain2\v190\src\usart.c + ..\src\board\psc\v190\src\tim.c - board_strain2_v190.c + board_psc_v190.c 1 - ..\src\board\strain2\v190\src\board_strain2_v190.c + ..\src\board\psc\v190\src\board_psc_v190.c - board-strain2-v1B0 + board-sg3-v190 0 @@ -48231,57 +54293,47 @@ adc.c 1 - ..\src\board\strain2\v1B0\src\adc.c + ..\src\board\sg3\v190\src\adc.c - board_strain2_v1B0.c + board_sg3_v190.c 1 - ..\src\board\strain2\v1B0\src\board_strain2_v1B0.c + ..\src\board\sg3\v190\src\board_sg3_v190.c can.c 1 - ..\src\board\strain2\v1B0\src\can.c + ..\src\board\sg3\v190\src\can.c dma.c 1 - ..\src\board\strain2\v1B0\src\dma.c + ..\src\board\sg3\v190\src\dma.c gpio.c 1 - ..\src\board\strain2\v1B0\src\gpio.c + ..\src\board\sg3\v190\src\gpio.c i2c.c 1 - ..\src\board\strain2\v1B0\src\i2c.c - - - rng.c - 1 - ..\src\board\strain2\v1B0\src\rng.c + ..\src\board\sg3\v190\src\i2c.c stm32l4xx_hal_msp.c 1 - ..\src\board\strain2\v1B0\src\stm32l4xx_hal_msp.c + ..\src\board\sg3\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\strain2\v1B0\src\tim.c - - - usart.c - 1 - ..\src\board\strain2\v1B0\src\usart.c + ..\src\board\sg3\v190\src\tim.c - board-psc-v190 + board-mtb4-v190 0 @@ -48352,50 +54404,60 @@ + + adc.c + 1 + ..\src\board\mtb4\v190\src\adc.c + + + board_mtb4_v190.c + 1 + ..\src\board\mtb4\v190\src\board_mtb4_v190.c + can.c 1 - ..\src\board\psc\v190\src\can.c + ..\src\board\mtb4\v190\src\can.c dma.c 1 - ..\src\board\psc\v190\src\dma.c + ..\src\board\mtb4\v190\src\dma.c gpio.c 1 - ..\src\board\psc\v190\src\gpio.c + ..\src\board\mtb4\v190\src\gpio.c i2c.c 1 - ..\src\board\psc\v190\src\i2c.c + ..\src\board\mtb4\v190\src\i2c.c rng.c 1 - ..\src\board\psc\v190\src\rng.c + ..\src\board\mtb4\v190\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\psc\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\psc\v190\src\tim.c + ..\src\board\mtb4\v190\src\tim.c - board_psc_v190.c + usart.c 1 - ..\src\board\psc\v190\src\board_psc_v190.c + ..\src\board\mtb4\v190\src\usart.c - board-sg3-v190 + board-mtb4-v172 0 @@ -48469,47 +54531,102 @@ adc.c 1 - ..\src\board\sg3\v190\src\adc.c + ..\src\board\mtb4\v172\src\adc.c - board_sg3_v190.c + can.c 1 - ..\src\board\sg3\v190\src\board_sg3_v190.c + ..\src\board\mtb4\v172\src\can.c + + + dma.c + 1 + ..\src\board\mtb4\v172\src\dma.c + + + gpio.c + 1 + ..\src\board\mtb4\v172\src\gpio.c + + + i2c.c + 1 + ..\src\board\mtb4\v172\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4\v172\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\mtb4\v172\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\mtb4\v172\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4\v172\src\usart.c + + + board_mtb4.c + 1 + ..\src\board\mtb4\v172\src\board_mtb4.c + + + + + board-mtb4c-v190 + + + board_mtb4c_v190.c + 1 + ..\src\board\mtb4c\v190\src\board_mtb4c_v190.c can.c 1 - ..\src\board\sg3\v190\src\can.c + ..\src\board\mtb4c\v190\src\can.c dma.c 1 - ..\src\board\sg3\v190\src\dma.c + ..\src\board\mtb4c\v190\src\dma.c gpio.c 1 - ..\src\board\sg3\v190\src\gpio.c + ..\src\board\mtb4c\v190\src\gpio.c i2c.c 1 - ..\src\board\sg3\v190\src\i2c.c + ..\src\board\mtb4c\v190\src\i2c.c stm32l4xx_hal_msp.c 1 - ..\src\board\sg3\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4c\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\sg3\v190\src\tim.c + ..\src\board\mtb4c\v190\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4c\v190\src\usart.c - board-mtb4-v190 + board-mtb4fap-v1D3 0 @@ -48581,59 +54698,59 @@ - adc.c + board_mtb4fap_v1D3.c 1 - ..\src\board\mtb4\v190\src\adc.c + ..\src\board\mtb4fap\V1D3\src\board_mtb4fap_v1D3.c - board_mtb4_v190.c + adc.c 1 - ..\src\board\mtb4\v190\src\board_mtb4_v190.c + ..\src\board\mtb4fap\V1D3\src\adc.c can.c 1 - ..\src\board\mtb4\v190\src\can.c + ..\src\board\mtb4fap\V1D3\src\can.c dma.c 1 - ..\src\board\mtb4\v190\src\dma.c + ..\src\board\mtb4fap\V1D3\src\dma.c gpio.c 1 - ..\src\board\mtb4\v190\src\gpio.c + ..\src\board\mtb4fap\V1D3\src\gpio.c i2c.c 1 - ..\src\board\mtb4\v190\src\i2c.c + ..\src\board\mtb4fap\V1D3\src\i2c.c rng.c 1 - ..\src\board\mtb4\v190\src\rng.c + ..\src\board\mtb4fap\V1D3\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4fap\V1D3\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4\v190\src\tim.c + ..\src\board\mtb4fap\V1D3\src\tim.c usart.c 1 - ..\src\board\mtb4\v190\src\usart.c + ..\src\board\mtb4fap\V1D3\src\usart.c - board-mtb4-v172 + board-strain2c-v1B0 0 @@ -48707,290 +54824,67 @@ adc.c 1 - ..\src\board\mtb4\v172\src\adc.c + ..\src\board\strain2c\v1B0\src\adc.c - can.c + board_strain2c_v1B0.c 1 - ..\src\board\mtb4\v172\src\can.c - - - dma.c - 1 - ..\src\board\mtb4\v172\src\dma.c - - - gpio.c - 1 - ..\src\board\mtb4\v172\src\gpio.c - - - i2c.c - 1 - ..\src\board\mtb4\v172\src\i2c.c - - - rng.c - 1 - ..\src\board\mtb4\v172\src\rng.c - - - stm32l4xx_hal_msp.c - 1 - ..\src\board\mtb4\v172\src\stm32l4xx_hal_msp.c - - - tim.c - 1 - ..\src\board\mtb4\v172\src\tim.c - - - usart.c - 1 - ..\src\board\mtb4\v172\src\usart.c - - - board_mtb4.c - 1 - ..\src\board\mtb4\v172\src\board_mtb4.c - - - - - board-mtb4c-v190 - - - 0 - 0 - 0 - 0 - 0 - 0 - 2 - 2 - 2 - 2 - 11 - - - 1 - - - - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 0 - 0 - 2 - 2 - 2 - 2 - 2 - - - - - - - - - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - - - - - - - - - - - - board_mtb4c_v190.c - 1 - ..\src\board\mtb4c\v190\src\board_mtb4c_v190.c + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c can.c 1 - ..\src\board\mtb4c\v190\src\can.c + ..\src\board\strain2c\v1B0\src\can.c dma.c 1 - ..\src\board\mtb4c\v190\src\dma.c + ..\src\board\strain2c\v1B0\src\dma.c gpio.c 1 - ..\src\board\mtb4c\v190\src\gpio.c + ..\src\board\strain2c\v1B0\src\gpio.c i2c.c 1 - ..\src\board\mtb4c\v190\src\i2c.c + ..\src\board\strain2c\v1B0\src\i2c.c - stm32l4xx_hal_msp.c + removed.main.c 1 - ..\src\board\mtb4c\v190\src\stm32l4xx_hal_msp.c + ..\src\board\strain2c\v1B0\src\removed.main.c - tim.c + removed.stm32l4xx_it.c 1 - ..\src\board\mtb4c\v190\src\tim.c + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c - usart.c + removed.system_stm32l4xx.c 1 - ..\src\board\mtb4c\v190\src\usart.c - - - - - board-mtb4fap-v1D3 - - - 0 - 0 - 0 - 0 - 0 - 0 - 2 - 2 - 2 - 2 - 11 - - - 1 - - - - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 0 - 0 - 2 - 2 - 2 - 2 - 2 - - - - - - - - - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - - - - - - - - - - - - board_mtb4fap_v1D3.c - 1 - ..\src\board\mtb4fap\V1D3\src\board_mtb4fap_v1D3.c - - - adc.c - 1 - ..\src\board\mtb4fap\V1D3\src\adc.c - - - can.c - 1 - ..\src\board\mtb4fap\V1D3\src\can.c - - - dma.c - 1 - ..\src\board\mtb4fap\V1D3\src\dma.c - - - gpio.c - 1 - ..\src\board\mtb4fap\V1D3\src\gpio.c - - - i2c.c - 1 - ..\src\board\mtb4fap\V1D3\src\i2c.c + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c rng.c 1 - ..\src\board\mtb4fap\V1D3\src\rng.c + ..\src\board\strain2c\v1B0\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4fap\V1D3\src\stm32l4xx_hal_msp.c + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4fap\V1D3\src\tim.c + ..\src\board\strain2c\v1B0\src\tim.c usart.c 1 - ..\src\board\mtb4fap\V1D3\src\usart.c + ..\src\board\strain2c\v1B0\src\usart.c @@ -49069,7 +54963,7 @@ - mtb4c-v190 + mtb4fap-v1D3 0x4 ARM-ADS 6180000::V6.18::ARMCLANG @@ -49111,7 +55005,7 @@ 1 .\v6-obj\ - stm32hal_mtb4c_v190 + stm32hal_mtb4fap_v1D3 0 1 0 @@ -49144,7 +55038,7 @@ 1 0 - cmd.exe /C copy .\v6-obj\stm32hal_mtb4c_v190.lib ..\lib\stm32hal.mtb4c.v190.lib + cmd.exe /C copy .\v6-obj\stm32hal_mtb4fap_v1D3.lib ..\lib\stm32hal.mtb4fap.v1D3.lib 0 0 @@ -49400,9 +55294,9 @@ 0 - USE_STM32HAL STM32HAL_BOARD_MTB4C STM32HAL_DRIVER_V190 + USE_STM32HAL STM32HAL_BOARD_MTB4FAP STM32HAL_DRIVER_V1D3 - ..\api;..\src\driver\stm32l4-v190\inc;..\src\board\mtb4c\v190\inc + ..\api;..\src\driver\stm32l4-v1D3\inc;..\src\board\mtb4fap\v1D3\inc @@ -50248,6 +56142,75 @@ driver-stm32l4-v190 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + stm32l4xx_hal.c @@ -51921,75 +57884,6 @@ driver-stm32l4-v1D3 - - - 0 - 0 - 0 - 0 - 0 - 0 - 2 - 2 - 2 - 2 - 11 - - - 1 - - - - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 0 - 0 - 2 - 2 - 2 - 2 - 2 - - - - - - - - - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - - - - - - - - - stm32l4xx_hal.c @@ -53024,57 +58918,181 @@ adc.c 1 - ..\src\board\strain2\v190\src\adc.c + ..\src\board\strain2\v190\src\adc.c + + + can.c + 1 + ..\src\board\strain2\v190\src\can.c + + + dma.c + 1 + ..\src\board\strain2\v190\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2\v190\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2\v190\src\i2c.c + + + rng.c + 1 + ..\src\board\strain2\v190\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2\v190\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2\v190\src\tim.c + + + usart.c + 1 + ..\src\board\strain2\v190\src\usart.c + + + board_strain2_v190.c + 1 + ..\src\board\strain2\v190\src\board_strain2_v190.c + + + + + board-strain2-v1B0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + + + + adc.c + 1 + ..\src\board\strain2\v1B0\src\adc.c + + + board_strain2_v1B0.c + 1 + ..\src\board\strain2\v1B0\src\board_strain2_v1B0.c can.c 1 - ..\src\board\strain2\v190\src\can.c + ..\src\board\strain2\v1B0\src\can.c dma.c 1 - ..\src\board\strain2\v190\src\dma.c + ..\src\board\strain2\v1B0\src\dma.c gpio.c 1 - ..\src\board\strain2\v190\src\gpio.c + ..\src\board\strain2\v1B0\src\gpio.c i2c.c 1 - ..\src\board\strain2\v190\src\i2c.c + ..\src\board\strain2\v1B0\src\i2c.c rng.c 1 - ..\src\board\strain2\v190\src\rng.c + ..\src\board\strain2\v1B0\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\strain2\v190\src\stm32l4xx_hal_msp.c + ..\src\board\strain2\v1B0\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\strain2\v190\src\tim.c + ..\src\board\strain2\v1B0\src\tim.c usart.c 1 - ..\src\board\strain2\v190\src\usart.c - - - board_strain2_v190.c - 1 - ..\src\board\strain2\v190\src\board_strain2_v190.c + ..\src\board\strain2\v1B0\src\usart.c - board-strain2-v1B0 + board-psc-v190 0 @@ -53145,60 +59163,50 @@ - - adc.c - 1 - ..\src\board\strain2\v1B0\src\adc.c - - - board_strain2_v1B0.c - 1 - ..\src\board\strain2\v1B0\src\board_strain2_v1B0.c - can.c 1 - ..\src\board\strain2\v1B0\src\can.c + ..\src\board\psc\v190\src\can.c dma.c 1 - ..\src\board\strain2\v1B0\src\dma.c + ..\src\board\psc\v190\src\dma.c gpio.c 1 - ..\src\board\strain2\v1B0\src\gpio.c + ..\src\board\psc\v190\src\gpio.c i2c.c 1 - ..\src\board\strain2\v1B0\src\i2c.c + ..\src\board\psc\v190\src\i2c.c rng.c 1 - ..\src\board\strain2\v1B0\src\rng.c + ..\src\board\psc\v190\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\strain2\v1B0\src\stm32l4xx_hal_msp.c + ..\src\board\psc\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\strain2\v1B0\src\tim.c + ..\src\board\psc\v190\src\tim.c - usart.c + board_psc_v190.c 1 - ..\src\board\strain2\v1B0\src\usart.c + ..\src\board\psc\v190\src\board_psc_v190.c - board-psc-v190 + board-sg3-v190 0 @@ -53270,49 +59278,49 @@ - can.c + adc.c 1 - ..\src\board\psc\v190\src\can.c + ..\src\board\sg3\v190\src\adc.c - dma.c + board_sg3_v190.c 1 - ..\src\board\psc\v190\src\dma.c + ..\src\board\sg3\v190\src\board_sg3_v190.c - gpio.c + can.c 1 - ..\src\board\psc\v190\src\gpio.c + ..\src\board\sg3\v190\src\can.c - i2c.c + dma.c 1 - ..\src\board\psc\v190\src\i2c.c + ..\src\board\sg3\v190\src\dma.c - rng.c + gpio.c 1 - ..\src\board\psc\v190\src\rng.c + ..\src\board\sg3\v190\src\gpio.c - stm32l4xx_hal_msp.c + i2c.c 1 - ..\src\board\psc\v190\src\stm32l4xx_hal_msp.c + ..\src\board\sg3\v190\src\i2c.c - tim.c + stm32l4xx_hal_msp.c 1 - ..\src\board\psc\v190\src\tim.c + ..\src\board\sg3\v190\src\stm32l4xx_hal_msp.c - board_psc_v190.c + tim.c 1 - ..\src\board\psc\v190\src\board_psc_v190.c + ..\src\board\sg3\v190\src\tim.c - board-sg3-v190 + board-mtb4-v190 0 @@ -53386,47 +59394,57 @@ adc.c 1 - ..\src\board\sg3\v190\src\adc.c + ..\src\board\mtb4\v190\src\adc.c - board_sg3_v190.c + board_mtb4_v190.c 1 - ..\src\board\sg3\v190\src\board_sg3_v190.c + ..\src\board\mtb4\v190\src\board_mtb4_v190.c can.c 1 - ..\src\board\sg3\v190\src\can.c + ..\src\board\mtb4\v190\src\can.c dma.c 1 - ..\src\board\sg3\v190\src\dma.c + ..\src\board\mtb4\v190\src\dma.c gpio.c 1 - ..\src\board\sg3\v190\src\gpio.c + ..\src\board\mtb4\v190\src\gpio.c i2c.c 1 - ..\src\board\sg3\v190\src\i2c.c + ..\src\board\mtb4\v190\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4\v190\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\sg3\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\sg3\v190\src\tim.c + ..\src\board\mtb4\v190\src\tim.c + + + usart.c + 1 + ..\src\board\mtb4\v190\src\usart.c - board-mtb4-v190 + board-mtb4-v172 0 @@ -53500,57 +59518,57 @@ adc.c 1 - ..\src\board\mtb4\v190\src\adc.c - - - board_mtb4_v190.c - 1 - ..\src\board\mtb4\v190\src\board_mtb4_v190.c + ..\src\board\mtb4\v172\src\adc.c can.c 1 - ..\src\board\mtb4\v190\src\can.c + ..\src\board\mtb4\v172\src\can.c dma.c 1 - ..\src\board\mtb4\v190\src\dma.c + ..\src\board\mtb4\v172\src\dma.c gpio.c 1 - ..\src\board\mtb4\v190\src\gpio.c + ..\src\board\mtb4\v172\src\gpio.c i2c.c 1 - ..\src\board\mtb4\v190\src\i2c.c + ..\src\board\mtb4\v172\src\i2c.c rng.c 1 - ..\src\board\mtb4\v190\src\rng.c + ..\src\board\mtb4\v172\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4\v172\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4\v190\src\tim.c + ..\src\board\mtb4\v172\src\tim.c usart.c 1 - ..\src\board\mtb4\v190\src\usart.c + ..\src\board\mtb4\v172\src\usart.c + + + board_mtb4.c + 1 + ..\src\board\mtb4\v172\src\board_mtb4.c - board-mtb4-v172 + board-mtb4c-v190 0 @@ -53622,104 +59640,155 @@ - adc.c + board_mtb4c_v190.c 1 - ..\src\board\mtb4\v172\src\adc.c + ..\src\board\mtb4c\v190\src\board_mtb4c_v190.c can.c 1 - ..\src\board\mtb4\v172\src\can.c + ..\src\board\mtb4c\v190\src\can.c dma.c 1 - ..\src\board\mtb4\v172\src\dma.c + ..\src\board\mtb4c\v190\src\dma.c gpio.c 1 - ..\src\board\mtb4\v172\src\gpio.c + ..\src\board\mtb4c\v190\src\gpio.c i2c.c 1 - ..\src\board\mtb4\v172\src\i2c.c - - - rng.c - 1 - ..\src\board\mtb4\v172\src\rng.c + ..\src\board\mtb4c\v190\src\i2c.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4\v172\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4c\v190\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4\v172\src\tim.c + ..\src\board\mtb4c\v190\src\tim.c usart.c 1 - ..\src\board\mtb4\v172\src\usart.c - - - board_mtb4.c - 1 - ..\src\board\mtb4\v172\src\board_mtb4.c + ..\src\board\mtb4c\v190\src\usart.c - board-mtb4c-v190 + board-mtb4fap-v1D3 - board_mtb4c_v190.c + board_mtb4fap_v1D3.c 1 - ..\src\board\mtb4c\v190\src\board_mtb4c_v190.c + ..\src\board\mtb4fap\V1D3\src\board_mtb4fap_v1D3.c + + + adc.c + 1 + ..\src\board\mtb4fap\V1D3\src\adc.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + can.c 1 - ..\src\board\mtb4c\v190\src\can.c + ..\src\board\mtb4fap\V1D3\src\can.c dma.c 1 - ..\src\board\mtb4c\v190\src\dma.c + ..\src\board\mtb4fap\V1D3\src\dma.c gpio.c 1 - ..\src\board\mtb4c\v190\src\gpio.c + ..\src\board\mtb4fap\V1D3\src\gpio.c i2c.c 1 - ..\src\board\mtb4c\v190\src\i2c.c + ..\src\board\mtb4fap\V1D3\src\i2c.c + + + rng.c + 1 + ..\src\board\mtb4fap\V1D3\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4c\v190\src\stm32l4xx_hal_msp.c + ..\src\board\mtb4fap\V1D3\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4c\v190\src\tim.c + ..\src\board\mtb4fap\V1D3\src\tim.c usart.c 1 - ..\src\board\mtb4c\v190\src\usart.c + ..\src\board\mtb4fap\V1D3\src\usart.c - board-mtb4fap-v1D3 + board-strain2c-v1B0 0 @@ -53791,54 +59860,69 @@ - board_mtb4fap_v1D3.c + adc.c 1 - ..\src\board\mtb4fap\V1D3\src\board_mtb4fap_v1D3.c + ..\src\board\strain2c\v1B0\src\adc.c - adc.c + board_strain2c_v1B0.c 1 - ..\src\board\mtb4fap\V1D3\src\adc.c + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c can.c 1 - ..\src\board\mtb4fap\V1D3\src\can.c + ..\src\board\strain2c\v1B0\src\can.c dma.c 1 - ..\src\board\mtb4fap\V1D3\src\dma.c + ..\src\board\strain2c\v1B0\src\dma.c gpio.c 1 - ..\src\board\mtb4fap\V1D3\src\gpio.c + ..\src\board\strain2c\v1B0\src\gpio.c i2c.c 1 - ..\src\board\mtb4fap\V1D3\src\i2c.c + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c rng.c 1 - ..\src\board\mtb4fap\V1D3\src\rng.c + ..\src\board\strain2c\v1B0\src\rng.c stm32l4xx_hal_msp.c 1 - ..\src\board\mtb4fap\V1D3\src\stm32l4xx_hal_msp.c + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c tim.c 1 - ..\src\board\mtb4fap\V1D3\src\tim.c + ..\src\board\strain2c\v1B0\src\tim.c usart.c 1 - ..\src\board\mtb4fap\V1D3\src\usart.c + ..\src\board\strain2c\v1B0\src\usart.c @@ -53917,7 +60001,7 @@ - mtb4fap-v1D3 + strain2c-v1B0 0x4 ARM-ADS 6180000::V6.18::ARMCLANG @@ -53959,7 +60043,7 @@ 1 .\v6-obj\ - stm32hal_mtb4fap_v1D3 + stm32hal_strain2c_v1B0 0 1 0 @@ -53992,7 +60076,7 @@ 1 0 - cmd.exe /C copy .\v6-obj\stm32hal_mtb4fap_v1D3.lib ..\lib\stm32hal.mtb4fap.v1D3.lib + cmd.exe /C copy .\v6-obj\stm32hal_strain2c_v1B0.lib ..\lib\stm32hal.strain2c.v1B0.lib 0 0 @@ -54248,9 +60332,9 @@ 0 - USE_STM32HAL STM32HAL_BOARD_MTB4FAP STM32HAL_DRIVER_V1D3 + USE_STM32HAL STM32HAL_BOARD_STRAIN2C STM32HAL_DRIVER_V1B0 - ..\api;..\src\driver\stm32l4-v1D3\inc;..\src\board\mtb4fap\v1D3\inc + ..\api;..\src\driver\stm32l4-v1B0\inc;..\src\board\strain2c\v1B0\inc @@ -55662,7 +61746,7 @@ 0 0 0 - 0 + 1 2 2 2 @@ -56838,6 +62922,75 @@ driver-stm32l4-v1D3 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + stm32l4xx_hal.c @@ -58637,6 +64790,75 @@ board-mtb4fap-v1D3 + + + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + 1 + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + + + + + + + + + board_mtb4fap_v1D3.c @@ -58647,57 +64869,6 @@ adc.c 1 ..\src\board\mtb4fap\V1D3\src\adc.c - - - 2 - 0 - 0 - 0 - 0 - 0 - 2 - 2 - 2 - 2 - 11 - - - 1 - - - - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 2 - 0 - 2 - 2 - 2 - 2 - 2 - 0 - 0 - 2 - 2 - 2 - 2 - 2 - - - - - - - - - can.c @@ -58741,6 +64912,76 @@ + + board-strain2c-v1B0 + + + adc.c + 1 + ..\src\board\strain2c\v1B0\src\adc.c + + + board_strain2c_v1B0.c + 1 + ..\src\board\strain2c\v1B0\src\board_strain2c_v1B0.c + + + can.c + 1 + ..\src\board\strain2c\v1B0\src\can.c + + + dma.c + 1 + ..\src\board\strain2c\v1B0\src\dma.c + + + gpio.c + 1 + ..\src\board\strain2c\v1B0\src\gpio.c + + + i2c.c + 1 + ..\src\board\strain2c\v1B0\src\i2c.c + + + removed.main.c + 1 + ..\src\board\strain2c\v1B0\src\removed.main.c + + + removed.stm32l4xx_it.c + 1 + ..\src\board\strain2c\v1B0\src\removed.stm32l4xx_it.c + + + removed.system_stm32l4xx.c + 1 + ..\src\board\strain2c\v1B0\src\removed.system_stm32l4xx.c + + + rng.c + 1 + ..\src\board\strain2c\v1B0\src\rng.c + + + stm32l4xx_hal_msp.c + 1 + ..\src\board\strain2c\v1B0\src\stm32l4xx_hal_msp.c + + + tim.c + 1 + ..\src\board\strain2c\v1B0\src\tim.c + + + usart.c + 1 + ..\src\board\strain2c\v1B0\src\usart.c + + + ::CMSIS @@ -58835,6 +65076,7 @@ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/adc.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/adc.h new file mode 100644 index 0000000000..bd6e2107be --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/adc.h @@ -0,0 +1,54 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file adc.h + * @brief This file contains all the function prototypes for + * the adc.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __ADC_H__ +#define __ADC_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern ADC_HandleTypeDef hadc1; +extern DMA_HandleTypeDef hdma_adc1; + + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_ADC1_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __ADC_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/can.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/can.h new file mode 100644 index 0000000000..165cace0d4 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/can.h @@ -0,0 +1,52 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file can.h + * @brief This file contains all the function prototypes for + * the can.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __CAN_H__ +#define __CAN_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern CAN_HandleTypeDef hcan1; + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_CAN1_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __CAN_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/dma.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/dma.h new file mode 100644 index 0000000000..d343621b3f --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/dma.h @@ -0,0 +1,52 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file dma.h + * @brief This file contains all the function prototypes for + * the dma.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __DMA_H__ +#define __DMA_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* DMA memory to memory transfer handles -------------------------------------*/ + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_DMA_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __DMA_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/gpio.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/gpio.h new file mode 100644 index 0000000000..45e27b1e06 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/gpio.h @@ -0,0 +1,49 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file gpio.h + * @brief This file contains all the function prototypes for + * the gpio.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __GPIO_H__ +#define __GPIO_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_GPIO_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif +#endif /*__ GPIO_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/i2c.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/i2c.h new file mode 100644 index 0000000000..f35a6ccd09 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/i2c.h @@ -0,0 +1,60 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file i2c.h + * @brief This file contains all the function prototypes for + * the i2c.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __I2C_H__ +#define __I2C_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern I2C_HandleTypeDef hi2c1; + +extern I2C_HandleTypeDef hi2c2; +// IIT-EXT +extern DMA_HandleTypeDef hdma_i2c1_tx; +extern DMA_HandleTypeDef hdma_i2c1_rx; +extern DMA_HandleTypeDef hdma_i2c2_tx; +extern DMA_HandleTypeDef hdma_i2c2_rx; + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_I2C1_Init(void); +void MX_I2C2_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __I2C_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/main.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/main.h new file mode 100644 index 0000000000..67ce80594b --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/main.h @@ -0,0 +1,114 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file : main.h + * @brief : Header for main.c file. + * This file contains the common defines of the application. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MAIN_H +#define __MAIN_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +// IIT-EXT +#if defined(USE_STM32HAL) + #include "stm32hal.h" +#else +#include "stm32l4xx_hal.h" +#endif +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Exported types ------------------------------------------------------------*/ +/* USER CODE BEGIN ET */ + +/* USER CODE END ET */ + +/* Exported constants --------------------------------------------------------*/ +/* USER CODE BEGIN EC */ + +/* USER CODE END EC */ + +/* Exported macro ------------------------------------------------------------*/ +/* USER CODE BEGIN EM */ + +/* USER CODE END EM */ + +/* Exported functions prototypes ---------------------------------------------*/ +void Error_Handler(void); + +/* USER CODE BEGIN EFP */ + +/* USER CODE END EFP */ + +/* Private defines -----------------------------------------------------------*/ +#define BNO055_BOOT_Pin GPIO_PIN_13 +#define BNO055_BOOT_GPIO_Port GPIOC +#define BNO055_INT_Pin GPIO_PIN_10 +#define BNO055_INT_GPIO_Port GPIOC +#define BNO055_RESET_Pin GPIO_PIN_12 +#define BNO055_RESET_GPIO_Port GPIOC +#define EN_OSC_Pin GPIO_PIN_11 +#define EN_OSC_GPIO_Port GPIOA +#define W_STRAIN6_Pin GPIO_PIN_9 +#define W_STRAIN6_GPIO_Port GPIOC +#define STRAIN2_Pin GPIO_PIN_1 +#define STRAIN2_GPIO_Port GPIOC +#define STRAIN1_Pin GPIO_PIN_0 +#define STRAIN1_GPIO_Port GPIOC +#define W_STRAIN4_Pin GPIO_PIN_7 +#define W_STRAIN4_GPIO_Port GPIOC +#define W_STRAIN5_Pin GPIO_PIN_8 +#define W_STRAIN5_GPIO_Port GPIOC +#define STRAIN3_Pin GPIO_PIN_2 +#define STRAIN3_GPIO_Port GPIOC +#define CAN1_SHDN_Pin GPIO_PIN_0 +#define CAN1_SHDN_GPIO_Port GPIOB +#define W_STRAIN3_Pin GPIO_PIN_6 +#define W_STRAIN3_GPIO_Port GPIOC +#define EN_2V8_Pin GPIO_PIN_15 +#define EN_2V8_GPIO_Port GPIOB +#define STRAIN4_Pin GPIO_PIN_3 +#define STRAIN4_GPIO_Port GPIOC +#define STRAIN5_Pin GPIO_PIN_0 +#define STRAIN5_GPIO_Port GPIOA +#define CAN1_STB_Pin GPIO_PIN_1 +#define CAN1_STB_GPIO_Port GPIOB +#define PG_3V3_Pin GPIO_PIN_13 +#define PG_3V3_GPIO_Port GPIOB +#define STRAIN6_Pin GPIO_PIN_1 +#define STRAIN6_GPIO_Port GPIOA +#define W_STRAIN1_Pin GPIO_PIN_4 +#define W_STRAIN1_GPIO_Port GPIOC +#define W_STRAIN2_Pin GPIO_PIN_5 +#define W_STRAIN2_GPIO_Port GPIOC +#define LED_Pin GPIO_PIN_11 +#define LED_GPIO_Port GPIOB +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +#ifdef __cplusplus +} +#endif + +#endif /* __MAIN_H */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/removed.stm32l4xx_hal_conf.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/removed.stm32l4xx_hal_conf.h new file mode 100644 index 0000000000..eaef02ec4b --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/removed.stm32l4xx_hal_conf.h @@ -0,0 +1,482 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32l4xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32l4xx_hal_conf.h. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32L4xx_HAL_CONF_H +#define STM32L4xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +/*#define HAL_CRYP_MODULE_ENABLED */ +#define HAL_CAN_MODULE_ENABLED +/*#define HAL_COMP_MODULE_ENABLED */ +/*#define HAL_CRC_MODULE_ENABLED */ +/*#define HAL_CRYP_MODULE_ENABLED */ +/*#define HAL_DAC_MODULE_ENABLED */ +/*#define HAL_DCMI_MODULE_ENABLED */ +/*#define HAL_DMA2D_MODULE_ENABLED */ +/*#define HAL_DFSDM_MODULE_ENABLED */ +/*#define HAL_DSI_MODULE_ENABLED */ +/*#define HAL_FIREWALL_MODULE_ENABLED */ +/*#define HAL_GFXMMU_MODULE_ENABLED */ +/*#define HAL_HCD_MODULE_ENABLED */ +/*#define HAL_HASH_MODULE_ENABLED */ +/*#define HAL_I2S_MODULE_ENABLED */ +/*#define HAL_IRDA_MODULE_ENABLED */ +/*#define HAL_IWDG_MODULE_ENABLED */ +/*#define HAL_LTDC_MODULE_ENABLED */ +/*#define HAL_LCD_MODULE_ENABLED */ +/*#define HAL_LPTIM_MODULE_ENABLED */ +/*#define HAL_MMC_MODULE_ENABLED */ +/*#define HAL_NAND_MODULE_ENABLED */ +/*#define HAL_NOR_MODULE_ENABLED */ +/*#define HAL_OPAMP_MODULE_ENABLED */ +/*#define HAL_OSPI_MODULE_ENABLED */ +/*#define HAL_OSPI_MODULE_ENABLED */ +/*#define HAL_PCD_MODULE_ENABLED */ +/*#define HAL_PKA_MODULE_ENABLED */ +/*#define HAL_QSPI_MODULE_ENABLED */ +/*#define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RNG_MODULE_ENABLED +/*#define HAL_RTC_MODULE_ENABLED */ +/*#define HAL_SAI_MODULE_ENABLED */ +/*#define HAL_SD_MODULE_ENABLED */ +/*#define HAL_SMBUS_MODULE_ENABLED */ +/*#define HAL_SMARTCARD_MODULE_ENABLED */ +/*#define HAL_SPI_MODULE_ENABLED */ +/*#define HAL_SRAM_MODULE_ENABLED */ +/*#define HAL_SWPMI_MODULE_ENABLED */ +#define HAL_TIM_MODULE_ENABLED +/*#define HAL_TSC_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/*#define HAL_USART_MODULE_ENABLED */ +/*#define HAL_WWDG_MODULE_ENABLED */ +/*#define HAL_EXTI_MODULE_ENABLED */ +/*#define HAL_PSSI_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)10000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal Multiple Speed oscillator (MSI) default value. + * This value is the default MSI range value after Reset. + */ +#if !defined (MSI_VALUE) + #define MSI_VALUE ((uint32_t)4000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* MSI_VALUE */ +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG. + * This internal oscillator is mainly dedicated to provide a high precision clock to + * the USB peripheral by means of a special Clock Recovery System (CRS) circuitry. + * When the CRS is not used, the HSI48 RC oscillator runs on it default frequency + * which is subject to manufacturing process variations. + */ +#if !defined (HSI48_VALUE) + #define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz. + The real value my vary depending on manufacturing process variations.*/ +#endif /* HSI48_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature.*/ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for SAI1 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI1_CLOCK_VALUE) + #define EXTERNAL_SAI1_CLOCK_VALUE 2097000U /*!< Value of the SAI1 External clock source in Hz*/ +#endif /* EXTERNAL_SAI1_CLOCK_VALUE */ + +/** + * @brief External clock source for SAI2 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI2_CLOCK_VALUE) + #define EXTERNAL_SAI2_CLOCK_VALUE 48000U /*!< Value of the SAI2 External clock source in Hz*/ +#endif /* EXTERNAL_SAI2_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ + +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 0U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_ENABLE 1U + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ + #define USE_FULL_ASSERT 1U + +/* ################## Register callback feature configuration ############### */ +/** + * @brief Set below the peripheral configuration to "1U" to add the support + * of HAL callback registration/deregistration feature for the HAL + * driver(s). This allows user application to provide specific callback + * functions thanks to HAL_PPP_RegisterCallback() rather than overwriting + * the default weak callback functions (see each stm32l4xx_hal_ppp.h file + * for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef + * for each PPP peripheral). + */ +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U +#define USE_HAL_COMP_REGISTER_CALLBACKS 0U +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U +#define USE_HAL_GFXMMU_REGISTER_CALLBACKS 0U +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U +#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U +#define USE_HAL_OSPI_REGISTER_CALLBACKS 0U +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U +#define USE_HAL_SD_REGISTER_CALLBACKS 0U +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U +#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U +#define USE_HAL_TSC_REGISTER_CALLBACKS 0U +#define USE_HAL_UART_REGISTER_CALLBACKS 0U +#define USE_HAL_USART_REGISTER_CALLBACKS 0U +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver + * Activated: CRC code is present inside driver + * Deactivated: CRC code cleaned from driver + */ + +#define USE_SPI_CRC 0U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32l4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32l4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32l4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32l4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32l4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32l4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32l4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32l4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "stm32l4xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32l4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32l4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32l4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32l4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32l4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32l4xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32l4xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_GFXMMU_MODULE_ENABLED + #include "stm32l4xx_hal_gfxmmu.h" +#endif /* HAL_GFXMMU_MODULE_ENABLED */ + +#ifdef HAL_FIREWALL_MODULE_ENABLED + #include "stm32l4xx_hal_firewall.h" +#endif /* HAL_FIREWALL_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32l4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32l4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32l4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32l4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32l4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32l4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LCD_MODULE_ENABLED + #include "stm32l4xx_hal_lcd.h" +#endif /* HAL_LCD_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32l4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32l4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32l4xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32l4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32l4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED + #include "stm32l4xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_OSPI_MODULE_ENABLED + #include "stm32l4xx_hal_ospi.h" +#endif /* HAL_OSPI_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32l4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_PKA_MODULE_ENABLED + #include "stm32l4xx_hal_pka.h" +#endif /* HAL_PKA_MODULE_ENABLED */ + +#ifdef HAL_PSSI_MODULE_ENABLED + #include "stm32l4xx_hal_pssi.h" +#endif /* HAL_PSSI_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32l4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32l4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32l4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32l4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32l4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32l4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32l4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32l4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32l4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32l4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "stm32l4xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32l4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_TSC_MODULE_ENABLED + #include "stm32l4xx_hal_tsc.h" +#endif /* HAL_TSC_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32l4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32l4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32l4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t *file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32L4xx_HAL_CONF_H */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/rng.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/rng.h new file mode 100644 index 0000000000..a9249bed53 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/rng.h @@ -0,0 +1,52 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file rng.h + * @brief This file contains all the function prototypes for + * the rng.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __RNG_H__ +#define __RNG_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern RNG_HandleTypeDef hrng; + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_RNG_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __RNG_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/stm32l4xx_it.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/stm32l4xx_it.h new file mode 100644 index 0000000000..57dad14f5f --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/stm32l4xx_it.h @@ -0,0 +1,85 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32l4xx_it.h + * @brief This file contains the headers of the interrupt handlers. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32L4xx_IT_H +#define __STM32L4xx_IT_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Exported types ------------------------------------------------------------*/ +/* USER CODE BEGIN ET */ + +/* USER CODE END ET */ + +/* Exported constants --------------------------------------------------------*/ +/* USER CODE BEGIN EC */ + +/* USER CODE END EC */ + +/* Exported macro ------------------------------------------------------------*/ +/* USER CODE BEGIN EM */ + +/* USER CODE END EM */ + +/* Exported functions prototypes ---------------------------------------------*/ +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void SVC_Handler(void); +void DebugMon_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); +void DMA1_Channel1_IRQHandler(void); +void DMA1_Channel4_IRQHandler(void); +void DMA1_Channel5_IRQHandler(void); +void DMA1_Channel6_IRQHandler(void); +void DMA1_Channel7_IRQHandler(void); +void ADC1_IRQHandler(void); +void CAN1_TX_IRQHandler(void); +void CAN1_RX0_IRQHandler(void); +void TIM1_BRK_TIM15_IRQHandler(void); +void TIM1_UP_TIM16_IRQHandler(void); +void I2C1_EV_IRQHandler(void); +void I2C1_ER_IRQHandler(void); +void I2C2_EV_IRQHandler(void); +void I2C2_ER_IRQHandler(void); +void USART1_IRQHandler(void); +void USART2_IRQHandler(void); +void TIM6_DAC_IRQHandler(void); +void DMA2_Channel6_IRQHandler(void); +void DMA2_Channel7_IRQHandler(void); +/* USER CODE BEGIN EFP */ + +/* USER CODE END EFP */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32L4xx_IT_H */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/tim.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/tim.h new file mode 100644 index 0000000000..defdc95d2f --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/tim.h @@ -0,0 +1,58 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file tim.h + * @brief This file contains all the function prototypes for + * the tim.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __TIM_H__ +#define __TIM_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern TIM_HandleTypeDef htim6; + +extern TIM_HandleTypeDef htim15; + +extern TIM_HandleTypeDef htim16; + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_TIM6_Init(void); +void MX_TIM15_Init(void); +void MX_TIM16_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __TIM_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/usart.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/usart.h new file mode 100644 index 0000000000..a429df3603 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/inc/usart.h @@ -0,0 +1,55 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file usart.h + * @brief This file contains all the function prototypes for + * the usart.c file + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USART_H__ +#define __USART_H__ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +extern UART_HandleTypeDef huart1; + +extern UART_HandleTypeDef huart2; + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +void MX_USART1_UART_Init(void); +void MX_USART2_UART_Init(void); + +/* USER CODE BEGIN Prototypes */ + +/* USER CODE END Prototypes */ + +#ifdef __cplusplus +} +#endif + +#endif /* __USART_H__ */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/adc.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/adc.c new file mode 100644 index 0000000000..d837c7abaf --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/adc.c @@ -0,0 +1,239 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file adc.c + * @brief This file provides code for the configuration + * of the ADC instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "adc.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +ADC_HandleTypeDef hadc1; +DMA_HandleTypeDef hdma_adc1; + +/* ADC1 init function */ +void MX_ADC1_Init(void) +{ + + /* USER CODE BEGIN ADC1_Init 0 */ + + /* USER CODE END ADC1_Init 0 */ + + ADC_ChannelConfTypeDef sConfig = {0}; + + /* USER CODE BEGIN ADC1_Init 1 */ + + /* USER CODE END ADC1_Init 1 */ + + /** Common config + */ + hadc1.Instance = ADC1; + hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV2; + hadc1.Init.Resolution = ADC_RESOLUTION_12B; + hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE; + hadc1.Init.EOCSelection = ADC_EOC_SEQ_CONV; + hadc1.Init.LowPowerAutoWait = DISABLE; + hadc1.Init.ContinuousConvMode = ENABLE; + hadc1.Init.NbrOfConversion = 6; + hadc1.Init.DiscontinuousConvMode = DISABLE; + hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START; + hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; + hadc1.Init.DMAContinuousRequests = ENABLE; + hadc1.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN; + hadc1.Init.OversamplingMode = ENABLE; + hadc1.Init.Oversampling.Ratio = ADC_OVERSAMPLING_RATIO_32; + hadc1.Init.Oversampling.RightBitShift = ADC_RIGHTBITSHIFT_4; + hadc1.Init.Oversampling.TriggeredMode = ADC_TRIGGEREDMODE_SINGLE_TRIGGER; + hadc1.Init.Oversampling.OversamplingStopReset = ADC_REGOVERSAMPLING_CONTINUED_MODE; + if (HAL_ADC_Init(&hadc1) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_1; + sConfig.Rank = ADC_REGULAR_RANK_1; + sConfig.SamplingTime = ADC_SAMPLETIME_12CYCLES_5; + sConfig.SingleDiff = ADC_SINGLE_ENDED; + sConfig.OffsetNumber = ADC_OFFSET_NONE; + sConfig.Offset = 0; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_2; + sConfig.Rank = ADC_REGULAR_RANK_2; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_3; + sConfig.Rank = ADC_REGULAR_RANK_3; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_4; + sConfig.Rank = ADC_REGULAR_RANK_4; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_5; + sConfig.Rank = ADC_REGULAR_RANK_5; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Regular Channel + */ + sConfig.Channel = ADC_CHANNEL_6; + sConfig.Rank = ADC_REGULAR_RANK_6; + if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN ADC1_Init 2 */ + + /* USER CODE END ADC1_Init 2 */ + +} + +void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle) +{ + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + if(adcHandle->Instance==ADC1) + { + /* USER CODE BEGIN ADC1_MspInit 0 */ + + /* USER CODE END ADC1_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; + PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + /* ADC1 clock enable */ + __HAL_RCC_ADC_CLK_ENABLE(); + + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**ADC1 GPIO Configuration + PC1 ------> ADC1_IN2 + PC0 ------> ADC1_IN1 + PC2 ------> ADC1_IN3 + PC3 ------> ADC1_IN4 + PA0 ------> ADC1_IN5 + PA1 ------> ADC1_IN6 + */ + GPIO_InitStruct.Pin = STRAIN2_Pin|STRAIN1_Pin|STRAIN3_Pin|STRAIN4_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = STRAIN5_Pin|STRAIN6_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* ADC1 DMA Init */ + /* ADC1 Init */ + hdma_adc1.Instance = DMA1_Channel1; + hdma_adc1.Init.Request = DMA_REQUEST_0; + hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_adc1.Init.MemInc = DMA_MINC_ENABLE; + hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + hdma_adc1.Init.Mode = DMA_CIRCULAR; + hdma_adc1.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_adc1) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(adcHandle,DMA_Handle,hdma_adc1); + + /* ADC1 interrupt Init */ + HAL_NVIC_SetPriority(ADC1_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(ADC1_IRQn); + /* USER CODE BEGIN ADC1_MspInit 1 */ + + /* USER CODE END ADC1_MspInit 1 */ + } +} + +void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle) +{ + + if(adcHandle->Instance==ADC1) + { + /* USER CODE BEGIN ADC1_MspDeInit 0 */ + + /* USER CODE END ADC1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_ADC_CLK_DISABLE(); + + /**ADC1 GPIO Configuration + PC1 ------> ADC1_IN2 + PC0 ------> ADC1_IN1 + PC2 ------> ADC1_IN3 + PC3 ------> ADC1_IN4 + PA0 ------> ADC1_IN5 + PA1 ------> ADC1_IN6 + */ + HAL_GPIO_DeInit(GPIOC, STRAIN2_Pin|STRAIN1_Pin|STRAIN3_Pin|STRAIN4_Pin); + + HAL_GPIO_DeInit(GPIOA, STRAIN5_Pin|STRAIN6_Pin); + + /* ADC1 DMA DeInit */ + HAL_DMA_DeInit(adcHandle->DMA_Handle); + + /* ADC1 interrupt Deinit */ + HAL_NVIC_DisableIRQ(ADC1_IRQn); + /* USER CODE BEGIN ADC1_MspDeInit 1 */ + + /* USER CODE END ADC1_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/board_strain2c_v1B0.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/board_strain2c_v1B0.c new file mode 100644 index 0000000000..fd629b55dc --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/board_strain2c_v1B0.c @@ -0,0 +1,260 @@ +/* + * Copyright (C) 2020 iCub Facility - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it + * website: www.robotcub.org + * Permission is granted to copy, distribute, and/or modify this program + * under the terms of the GNU General Public License, version 2 or any + * later version published by the Free Software Foundation. + * + * A copy of the license can be found at + * http://www.robotcub.org/icub/license/gpl.txt + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details +*/ + + +// -------------------------------------------------------------------------------------------------------------------- +// - external dependencies +// -------------------------------------------------------------------------------------------------------------------- + +#include "stm32hal.h" + + +#include "string.h" + +// -------------------------------------------------------------------------------------------------------------------- +// - declaration of extern public interface +// -------------------------------------------------------------------------------------------------------------------- + +#include "stm32hal_board.h" + +// -------------------------------------------------------------------------------------------------------------------- +// - #define with internal scope +// -------------------------------------------------------------------------------------------------------------------- + +// used to remove code genrted by cubemx which we dont want. such as the init of the systick +#define STM32HAL_BSP_REMOVE_CUBEMX_CODE + +// used to SHOW that we have added static +#define STM32HAL_BSP_STATIC_SCOPE static + +// -------------------------------------------------------------------------------------------------------------------- +// - definition (and initialisation) of extern variables, but better using _get(), _set() +// -------------------------------------------------------------------------------------------------------------------- +// empty-section + + + +// -------------------------------------------------------------------------------------------------------------------- +// - typedef with internal scope +// -------------------------------------------------------------------------------------------------------------------- +// empty-section + + + +// -------------------------------------------------------------------------------------------------------------------- +// - declaration of static functions +// -------------------------------------------------------------------------------------------------------------------- + +// functions generated by cubemx and typically placed into main.c. +// i put them in static section AND I ADD THE KEYWORD "static" because their scope is local +STM32HAL_BSP_STATIC_SCOPE void SystemClock_Config(void); + + +// -------------------------------------------------------------------------------------------------------------------- +// - definition (and initialisation) of static variables +// -------------------------------------------------------------------------------------------------------------------- +// empty-section + + +// -------------------------------------------------------------------------------------------------------------------- +// - definition of extern public functions +// -------------------------------------------------------------------------------------------------------------------- + + +extern void stm32hal_board_init(void) +{ + // in here we get the code generated by cube-mx and present in main.c and we keep just what we need + + /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ + HAL_Init(); + + /* Configure the system clock */ + SystemClock_Config(); + + /* Initialize all configured peripherals */ + MX_GPIO_Init(); + MX_DMA_Init(); +// IIT-EXT: this funtion is called inside embot::hw::timer::init() MX_TIM6_Init(); +// IIT-EXT: this funtion is called inside embot::hw::can::init() MX_CAN1_Init(); +// IIT-EXT: this peripheral is not used: MX_USART1_UART_Init(); +// IIT-EXT: this funtion is called inside embot::hw::adc::init() MX_ADC1_Init(); +// IIT-EXT: this funtion is called inside embot::hw::i2c::init() MX_I2C1_Init(); +// IIT-EXT: this funtion is called inside embot::hw::i2c::init() MX_I2C2_Init(); +// IIT-EXT: this peripheral is not used: MX_USART2_UART_Init(); +// IIT-EXT: this funtion is called inside embot::hw::timer::init() MX_TIM7_Init(); +// IIT-EXT: this funtion is called inside embot::hw::timer::init() MX_TIM16_Init(); +// IIT-EXT: this funtion is called inside embot::hw::timer::init() MX_TIM15_Init(); + MX_RNG_Init(); + + } + + +// -------------------------------------------------------------------------------------------------------------------- +// - definition of funtions genrated by cube-mx which must be global..... sic! +// -------------------------------------------------------------------------------------------------------------------- + +/** + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) +{ + /* USER CODE BEGIN Error_Handler_Debug */ + /* User can add his own implementation to report the HAL error return state */ + + /* USER CODE END Error_Handler_Debug */ +} + + +// -------------------------------------------------------------------------------------------------------------------- +// - definition of static functions +// -------------------------------------------------------------------------------------------------------------------- + + +/** + * @brief System Clock Configuration + * @retval None + */ +STM32HAL_BSP_STATIC_SCOPE void SystemClock_Config(void) +{ +#if defined(CPU_AT_80MHZ) + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + + /** Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSI; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; + RCC_OscInitStruct.PLL.PLLM = 1; + RCC_OscInitStruct.PLL.PLLN = 10; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV7; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + Error_Handler(); + } + /** Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) + { + Error_Handler(); + } + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2 + |RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C2 + |RCC_PERIPHCLK_RNG|RCC_PERIPHCLK_ADC; + PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2; + PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1; + PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1; + PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1; + PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK; + PeriphClkInit.RngClockSelection = RCC_RNGCLKSOURCE_HSI48; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + /**Configure the main internal regulator output voltage + */ + if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK) + { + Error_Handler(); + } +#else + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSI; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + Error_Handler(); + } + /**Initializes the CPU, AHB and APB busses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK) + { + Error_Handler(); + } + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2 + |RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C2 + |RCC_PERIPHCLK_RNG|RCC_PERIPHCLK_ADC; + PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2; + PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1; + PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1; + PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1; + PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK; + PeriphClkInit.RngClockSelection = RCC_RNGCLKSOURCE_HSI48; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + /**Configure the main internal regulator output voltage + */ + if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK) + { + Error_Handler(); + } +#endif +} + +// previous driver v173 also had: +#if 0 + + /**Configure the Systick + */ + HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); + + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); + +#endif + + + + +// -------------------------------------------------------------------------------------------------------------------- +// - end-of-file (leave a blank line after) +// -------------------------------------------------------------------------------------------------------------------- + + + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/can.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/can.c new file mode 100644 index 0000000000..ec3d77c248 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/can.c @@ -0,0 +1,125 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file can.c + * @brief This file provides code for the configuration + * of the CAN instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "can.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +CAN_HandleTypeDef hcan1; + +/* CAN1 init function */ +void MX_CAN1_Init(void) +{ + + /* USER CODE BEGIN CAN1_Init 0 */ + + /* USER CODE END CAN1_Init 0 */ + + /* USER CODE BEGIN CAN1_Init 1 */ + + /* USER CODE END CAN1_Init 1 */ + hcan1.Instance = CAN1; + hcan1.Init.Prescaler = 10; + hcan1.Init.Mode = CAN_MODE_NORMAL; + hcan1.Init.SyncJumpWidth = CAN_SJW_1TQ; + hcan1.Init.TimeSeg1 = CAN_BS1_2TQ; + hcan1.Init.TimeSeg2 = CAN_BS2_5TQ; + hcan1.Init.TimeTriggeredMode = DISABLE; + hcan1.Init.AutoBusOff = ENABLE; + hcan1.Init.AutoWakeUp = ENABLE; + hcan1.Init.AutoRetransmission = ENABLE; + hcan1.Init.ReceiveFifoLocked = DISABLE; + hcan1.Init.TransmitFifoPriority = DISABLE; + if (HAL_CAN_Init(&hcan1) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN CAN1_Init 2 */ + + /* USER CODE END CAN1_Init 2 */ + +} + +void HAL_CAN_MspInit(CAN_HandleTypeDef* canHandle) +{ + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + if(canHandle->Instance==CAN1) + { + /* USER CODE BEGIN CAN1_MspInit 0 */ + + /* USER CODE END CAN1_MspInit 0 */ + /* CAN1 clock enable */ + __HAL_RCC_CAN1_CLK_ENABLE(); + + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**CAN1 GPIO Configuration + PB9 ------> CAN1_TX + PB8 ------> CAN1_RX + */ + GPIO_InitStruct.Pin = GPIO_PIN_9|GPIO_PIN_8; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF9_CAN1; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* CAN1 interrupt Init */ + HAL_NVIC_SetPriority(CAN1_TX_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); + HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); + /* USER CODE BEGIN CAN1_MspInit 1 */ + + /* USER CODE END CAN1_MspInit 1 */ + } +} + +void HAL_CAN_MspDeInit(CAN_HandleTypeDef* canHandle) +{ + + if(canHandle->Instance==CAN1) + { + /* USER CODE BEGIN CAN1_MspDeInit 0 */ + + /* USER CODE END CAN1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_CAN1_CLK_DISABLE(); + + /**CAN1 GPIO Configuration + PB9 ------> CAN1_TX + PB8 ------> CAN1_RX + */ + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_9|GPIO_PIN_8); + + /* CAN1 interrupt Deinit */ + HAL_NVIC_DisableIRQ(CAN1_TX_IRQn); + HAL_NVIC_DisableIRQ(CAN1_RX0_IRQn); + /* USER CODE BEGIN CAN1_MspDeInit 1 */ + + /* USER CODE END CAN1_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/dma.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/dma.c new file mode 100644 index 0000000000..60ddbe772e --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/dma.c @@ -0,0 +1,74 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file dma.c + * @brief This file provides code for the configuration + * of all the requested memory to memory DMA transfers. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "dma.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/*----------------------------------------------------------------------------*/ +/* Configure DMA */ +/*----------------------------------------------------------------------------*/ + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ + +/** + * Enable DMA controller clock + */ +void MX_DMA_Init(void) +{ + + /* DMA controller clock enable */ + __HAL_RCC_DMA1_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + + /* DMA interrupt init */ + /* DMA1_Channel1_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel1_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel1_IRQn); + /* DMA1_Channel4_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel4_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel4_IRQn); + /* DMA1_Channel5_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel5_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel5_IRQn); + /* DMA1_Channel6_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel6_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel6_IRQn); + /* DMA1_Channel7_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA1_Channel7_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel7_IRQn); + /* DMA2_Channel6_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Channel6_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA2_Channel6_IRQn); + /* DMA2_Channel7_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Channel7_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA2_Channel7_IRQn); + +} + +/* USER CODE BEGIN 2 */ + +/* USER CODE END 2 */ + diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/gpio.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/gpio.c new file mode 100644 index 0000000000..f0fd5f4b88 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/gpio.c @@ -0,0 +1,139 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file gpio.c + * @brief This file provides code for the configuration + * of all used GPIO pins. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "gpio.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/*----------------------------------------------------------------------------*/ +/* Configure GPIO */ +/*----------------------------------------------------------------------------*/ +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ + +/** Configure pins as + * Analog + * Input + * Output + * EVENT_OUT + * EXTI + * Free pins are configured automatically as Analog (this feature is enabled through + * the Code Generation settings) +*/ +void MX_GPIO_Init(void) +{ + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + + /* GPIO Ports Clock Enable */ + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOH_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOC, BNO055_BOOT_Pin|BNO055_RESET_Pin|W_STRAIN6_Pin|W_STRAIN4_Pin + |W_STRAIN5_Pin|W_STRAIN3_Pin|W_STRAIN1_Pin|W_STRAIN2_Pin, GPIO_PIN_RESET); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(EN_OSC_GPIO_Port, EN_OSC_Pin, GPIO_PIN_RESET); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOB, CAN1_SHDN_Pin|EN_2V8_Pin|CAN1_STB_Pin|LED_Pin, GPIO_PIN_RESET); + + /*Configure GPIO pins : PC14 PC15 PC11 */ + GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /*Configure GPIO pins : PCPin PCPin PCPin PCPin + PCPin PCPin PCPin PCPin */ + GPIO_InitStruct.Pin = BNO055_BOOT_Pin|BNO055_RESET_Pin|W_STRAIN6_Pin|W_STRAIN4_Pin + |W_STRAIN5_Pin|W_STRAIN3_Pin|W_STRAIN1_Pin|W_STRAIN2_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /*Configure GPIO pins : PB4 PB3 PB5 PB2 + PB12 */ + GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_3|GPIO_PIN_5|GPIO_PIN_2 + |GPIO_PIN_12; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /*Configure GPIO pins : PA15 PA12 PA8 PA5 + PA6 PA4 PA7 */ + GPIO_InitStruct.Pin = GPIO_PIN_15|GPIO_PIN_12|GPIO_PIN_8|GPIO_PIN_5 + |GPIO_PIN_6|GPIO_PIN_4|GPIO_PIN_7; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /*Configure GPIO pins : PH3 PH0 PH1 */ + GPIO_InitStruct.Pin = GPIO_PIN_3|GPIO_PIN_0|GPIO_PIN_1; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + /*Configure GPIO pin : PD2 */ + GPIO_InitStruct.Pin = GPIO_PIN_2; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + + /*Configure GPIO pin : PtPin */ + GPIO_InitStruct.Pin = BNO055_INT_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(BNO055_INT_GPIO_Port, &GPIO_InitStruct); + + /*Configure GPIO pin : PtPin */ + GPIO_InitStruct.Pin = EN_OSC_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + HAL_GPIO_Init(EN_OSC_GPIO_Port, &GPIO_InitStruct); + + /*Configure GPIO pins : PBPin PBPin PBPin PBPin */ + GPIO_InitStruct.Pin = CAN1_SHDN_Pin|EN_2V8_Pin|CAN1_STB_Pin|LED_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /*Configure GPIO pin : PtPin */ + GPIO_InitStruct.Pin = PG_3V3_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(PG_3V3_GPIO_Port, &GPIO_InitStruct); + +} + +/* USER CODE BEGIN 2 */ + +/* USER CODE END 2 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/i2c.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/i2c.c new file mode 100644 index 0000000000..4f23d57d1c --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/i2c.c @@ -0,0 +1,337 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file i2c.c + * @brief This file provides code for the configuration + * of the I2C instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "i2c.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +I2C_HandleTypeDef hi2c1; +I2C_HandleTypeDef hi2c2; +DMA_HandleTypeDef hdma_i2c1_tx; +DMA_HandleTypeDef hdma_i2c1_rx; +DMA_HandleTypeDef hdma_i2c2_tx; +DMA_HandleTypeDef hdma_i2c2_rx; + +/* I2C1 init function */ +void MX_I2C1_Init(void) +{ + + /* USER CODE BEGIN I2C1_Init 0 */ + + /* USER CODE END I2C1_Init 0 */ + + /* USER CODE BEGIN I2C1_Init 1 */ + + /* USER CODE END I2C1_Init 1 */ + hi2c1.Instance = I2C1; + hi2c1.Init.Timing = 0x00702991; + hi2c1.Init.OwnAddress1 = 0; + hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; + hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; + hi2c1.Init.OwnAddress2 = 0; + hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK; + hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; + hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; + if (HAL_I2C_Init(&hi2c1) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Analogue filter + */ + if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Digital filter + */ + if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN I2C1_Init 2 */ + + /* USER CODE END I2C1_Init 2 */ + +} +/* I2C2 init function */ +void MX_I2C2_Init(void) +{ + + /* USER CODE BEGIN I2C2_Init 0 */ + + /* USER CODE END I2C2_Init 0 */ + + /* USER CODE BEGIN I2C2_Init 1 */ + + /* USER CODE END I2C2_Init 1 */ + hi2c2.Instance = I2C2; + hi2c2.Init.Timing = 0x00702991; + hi2c2.Init.OwnAddress1 = 0; + hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; + hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; + hi2c2.Init.OwnAddress2 = 0; + hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK; + hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; + hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; + if (HAL_I2C_Init(&hi2c2) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Analogue filter + */ + if (HAL_I2CEx_ConfigAnalogFilter(&hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK) + { + Error_Handler(); + } + + /** Configure Digital filter + */ + if (HAL_I2CEx_ConfigDigitalFilter(&hi2c2, 0) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN I2C2_Init 2 */ + + /* USER CODE END I2C2_Init 2 */ + +} + +void HAL_I2C_MspInit(I2C_HandleTypeDef* i2cHandle) +{ + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + if(i2cHandle->Instance==I2C1) + { + /* USER CODE BEGIN I2C1_MspInit 0 */ + + /* USER CODE END I2C1_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C1; + PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**I2C1 GPIO Configuration + PB7 ------> I2C1_SDA + PB6 ------> I2C1_SCL + */ + GPIO_InitStruct.Pin = GPIO_PIN_7|GPIO_PIN_6; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF4_I2C1; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* I2C1 clock enable */ + __HAL_RCC_I2C1_CLK_ENABLE(); + + /* I2C1 DMA Init */ + /* I2C1_TX Init */ + hdma_i2c1_tx.Instance = DMA1_Channel6; + hdma_i2c1_tx.Init.Request = DMA_REQUEST_3; + hdma_i2c1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; + hdma_i2c1_tx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_i2c1_tx.Init.MemInc = DMA_MINC_ENABLE; + hdma_i2c1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_i2c1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_i2c1_tx.Init.Mode = DMA_NORMAL; + hdma_i2c1_tx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_i2c1_tx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(i2cHandle,hdmatx,hdma_i2c1_tx); + + /* I2C1_RX Init */ + hdma_i2c1_rx.Instance = DMA1_Channel7; + hdma_i2c1_rx.Init.Request = DMA_REQUEST_3; + hdma_i2c1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_i2c1_rx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_i2c1_rx.Init.MemInc = DMA_MINC_ENABLE; + hdma_i2c1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_i2c1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_i2c1_rx.Init.Mode = DMA_NORMAL; + hdma_i2c1_rx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_i2c1_rx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(i2cHandle,hdmarx,hdma_i2c1_rx); + + /* I2C1 interrupt Init */ + HAL_NVIC_SetPriority(I2C1_EV_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(I2C1_EV_IRQn); + HAL_NVIC_SetPriority(I2C1_ER_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(I2C1_ER_IRQn); + /* USER CODE BEGIN I2C1_MspInit 1 */ + + /* USER CODE END I2C1_MspInit 1 */ + } + else if(i2cHandle->Instance==I2C2) + { + /* USER CODE BEGIN I2C2_MspInit 0 */ + + /* USER CODE END I2C2_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C2; + PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + __HAL_RCC_GPIOB_CLK_ENABLE(); + /**I2C2 GPIO Configuration + PB14 ------> I2C2_SDA + PB10 ------> I2C2_SCL + */ + GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF4_I2C2; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* I2C2 clock enable */ + __HAL_RCC_I2C2_CLK_ENABLE(); + + /* I2C2 DMA Init */ + /* I2C2_TX Init */ + hdma_i2c2_tx.Instance = DMA1_Channel4; + hdma_i2c2_tx.Init.Request = DMA_REQUEST_3; + hdma_i2c2_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; + hdma_i2c2_tx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_i2c2_tx.Init.MemInc = DMA_MINC_ENABLE; + hdma_i2c2_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_i2c2_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_i2c2_tx.Init.Mode = DMA_NORMAL; + hdma_i2c2_tx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_i2c2_tx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(i2cHandle,hdmatx,hdma_i2c2_tx); + + /* I2C2_RX Init */ + hdma_i2c2_rx.Instance = DMA1_Channel5; + hdma_i2c2_rx.Init.Request = DMA_REQUEST_3; + hdma_i2c2_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_i2c2_rx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_i2c2_rx.Init.MemInc = DMA_MINC_ENABLE; + hdma_i2c2_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_i2c2_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_i2c2_rx.Init.Mode = DMA_NORMAL; + hdma_i2c2_rx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_i2c2_rx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(i2cHandle,hdmarx,hdma_i2c2_rx); + + /* I2C2 interrupt Init */ + HAL_NVIC_SetPriority(I2C2_EV_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(I2C2_EV_IRQn); + HAL_NVIC_SetPriority(I2C2_ER_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(I2C2_ER_IRQn); + /* USER CODE BEGIN I2C2_MspInit 1 */ + + /* USER CODE END I2C2_MspInit 1 */ + } +} + +void HAL_I2C_MspDeInit(I2C_HandleTypeDef* i2cHandle) +{ + + if(i2cHandle->Instance==I2C1) + { + /* USER CODE BEGIN I2C1_MspDeInit 0 */ + + /* USER CODE END I2C1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_I2C1_CLK_DISABLE(); + + /**I2C1 GPIO Configuration + PB7 ------> I2C1_SDA + PB6 ------> I2C1_SCL + */ + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7); + + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6); + + /* I2C1 DMA DeInit */ + HAL_DMA_DeInit(i2cHandle->hdmatx); + HAL_DMA_DeInit(i2cHandle->hdmarx); + + /* I2C1 interrupt Deinit */ + HAL_NVIC_DisableIRQ(I2C1_EV_IRQn); + HAL_NVIC_DisableIRQ(I2C1_ER_IRQn); + /* USER CODE BEGIN I2C1_MspDeInit 1 */ + + /* USER CODE END I2C1_MspDeInit 1 */ + } + else if(i2cHandle->Instance==I2C2) + { + /* USER CODE BEGIN I2C2_MspDeInit 0 */ + + /* USER CODE END I2C2_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_I2C2_CLK_DISABLE(); + + /**I2C2 GPIO Configuration + PB14 ------> I2C2_SDA + PB10 ------> I2C2_SCL + */ + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_14); + + HAL_GPIO_DeInit(GPIOB, GPIO_PIN_10); + + /* I2C2 DMA DeInit */ + HAL_DMA_DeInit(i2cHandle->hdmatx); + HAL_DMA_DeInit(i2cHandle->hdmarx); + + /* I2C2 interrupt Deinit */ + HAL_NVIC_DisableIRQ(I2C2_EV_IRQn); + HAL_NVIC_DisableIRQ(I2C2_ER_IRQn); + /* USER CODE BEGIN I2C2_MspDeInit 1 */ + + /* USER CODE END I2C2_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.main.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.main.c new file mode 100644 index 0000000000..0ead8a2db8 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.main.c @@ -0,0 +1,204 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file : main.c + * @brief : Main program body + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "main.h" +#include "adc.h" +#include "can.h" +#include "dma.h" +#include "i2c.h" +#include "rng.h" +#include "tim.h" +#include "usart.h" +#include "gpio.h" + +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Private typedef -----------------------------------------------------------*/ +/* USER CODE BEGIN PTD */ + +/* USER CODE END PTD */ + +/* Private define ------------------------------------------------------------*/ +/* USER CODE BEGIN PD */ +/* USER CODE END PD */ + +/* Private macro -------------------------------------------------------------*/ +/* USER CODE BEGIN PM */ + +/* USER CODE END PM */ + +/* Private variables ---------------------------------------------------------*/ + +/* USER CODE BEGIN PV */ + +/* USER CODE END PV */ + +/* Private function prototypes -----------------------------------------------*/ +void SystemClock_Config(void); +/* USER CODE BEGIN PFP */ + +/* USER CODE END PFP */ + +/* Private user code ---------------------------------------------------------*/ +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/** + * @brief The application entry point. + * @retval int + */ +int main(void) +{ + /* USER CODE BEGIN 1 */ + + /* USER CODE END 1 */ + + /* MCU Configuration--------------------------------------------------------*/ + + /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ + HAL_Init(); + + /* USER CODE BEGIN Init */ + + /* USER CODE END Init */ + + /* Configure the system clock */ + SystemClock_Config(); + + /* USER CODE BEGIN SysInit */ + + /* USER CODE END SysInit */ + + /* Initialize all configured peripherals */ + MX_GPIO_Init(); + MX_CAN1_Init(); + MX_I2C1_Init(); + MX_I2C2_Init(); + MX_TIM6_Init(); + MX_DMA_Init(); + MX_USART2_UART_Init(); + MX_USART1_UART_Init(); + MX_ADC1_Init(); + MX_RNG_Init(); + MX_TIM15_Init(); + MX_TIM16_Init(); + /* USER CODE BEGIN 2 */ + + /* USER CODE END 2 */ + + /* Infinite loop */ + /* USER CODE BEGIN WHILE */ + while (1) + { + /* USER CODE END WHILE */ + + /* USER CODE BEGIN 3 */ + } + /* USER CODE END 3 */ +} + +/** + * @brief System Clock Configuration + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + + /** Configure the main internal regulator output voltage + */ + if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK) + { + Error_Handler(); + } + + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48|RCC_OSCILLATORTYPE_HSI; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; + RCC_OscInitStruct.PLL.PLLM = 1; + RCC_OscInitStruct.PLL.PLLN = 10; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV7; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + Error_Handler(); + } + + /** Initializes the CPU, AHB and APB buses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) + { + Error_Handler(); + } +} + +/* USER CODE BEGIN 4 */ + +/* USER CODE END 4 */ + +/** + * @brief This function is executed in case of error occurrence. + * @retval None + */ +void Error_Handler(void) +{ + /* USER CODE BEGIN Error_Handler_Debug */ + /* User can add his own implementation to report the HAL error return state */ + __disable_irq(); + while (1) + { + } + /* USER CODE END Error_Handler_Debug */ +} + +#ifdef USE_FULL_ASSERT +/** + * @brief Reports the name of the source file and the source line number + * where the assert_param error has occurred. + * @param file: pointer to the source file name + * @param line: assert_param error line source number + * @retval None + */ +void assert_failed(uint8_t *file, uint32_t line) +{ + /* USER CODE BEGIN 6 */ + /* User can add his own implementation to report the file name and line number, + ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ + /* USER CODE END 6 */ +} +#endif /* USE_FULL_ASSERT */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.stm32l4xx_it.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.stm32l4xx_it.c new file mode 100644 index 0000000000..c10bec2819 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.stm32l4xx_it.c @@ -0,0 +1,484 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32l4xx_it.c + * @brief Interrupt Service Routines. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" +#include "stm32l4xx_it.h" +/* Private includes ----------------------------------------------------------*/ +/* USER CODE BEGIN Includes */ +/* USER CODE END Includes */ + +/* Private typedef -----------------------------------------------------------*/ +/* USER CODE BEGIN TD */ + +/* USER CODE END TD */ + +/* Private define ------------------------------------------------------------*/ +/* USER CODE BEGIN PD */ + +/* USER CODE END PD */ + +/* Private macro -------------------------------------------------------------*/ +/* USER CODE BEGIN PM */ + +/* USER CODE END PM */ + +/* Private variables ---------------------------------------------------------*/ +/* USER CODE BEGIN PV */ + +/* USER CODE END PV */ + +/* Private function prototypes -----------------------------------------------*/ +/* USER CODE BEGIN PFP */ + +/* USER CODE END PFP */ + +/* Private user code ---------------------------------------------------------*/ +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/* External variables --------------------------------------------------------*/ +extern DMA_HandleTypeDef hdma_adc1; +extern ADC_HandleTypeDef hadc1; +extern CAN_HandleTypeDef hcan1; +extern DMA_HandleTypeDef hdma_i2c1_tx; +extern DMA_HandleTypeDef hdma_i2c1_rx; +extern DMA_HandleTypeDef hdma_i2c2_tx; +extern DMA_HandleTypeDef hdma_i2c2_rx; +extern I2C_HandleTypeDef hi2c1; +extern I2C_HandleTypeDef hi2c2; +extern TIM_HandleTypeDef htim6; +extern TIM_HandleTypeDef htim15; +extern TIM_HandleTypeDef htim16; +extern DMA_HandleTypeDef hdma_usart1_tx; +extern DMA_HandleTypeDef hdma_usart1_rx; +extern UART_HandleTypeDef huart1; +extern UART_HandleTypeDef huart2; +/* USER CODE BEGIN EV */ + +/* USER CODE END EV */ + +/******************************************************************************/ +/* Cortex-M4 Processor Interruption and Exception Handlers */ +/******************************************************************************/ +/** + * @brief This function handles Non maskable interrupt. + */ +void NMI_Handler(void) +{ + /* USER CODE BEGIN NonMaskableInt_IRQn 0 */ + + /* USER CODE END NonMaskableInt_IRQn 0 */ + /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ + while (1) + { + } + /* USER CODE END NonMaskableInt_IRQn 1 */ +} + +/** + * @brief This function handles Hard fault interrupt. + */ +void HardFault_Handler(void) +{ + /* USER CODE BEGIN HardFault_IRQn 0 */ + + /* USER CODE END HardFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_HardFault_IRQn 0 */ + /* USER CODE END W1_HardFault_IRQn 0 */ + } +} + +/** + * @brief This function handles Memory management fault. + */ +void MemManage_Handler(void) +{ + /* USER CODE BEGIN MemoryManagement_IRQn 0 */ + + /* USER CODE END MemoryManagement_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */ + /* USER CODE END W1_MemoryManagement_IRQn 0 */ + } +} + +/** + * @brief This function handles Prefetch fault, memory access fault. + */ +void BusFault_Handler(void) +{ + /* USER CODE BEGIN BusFault_IRQn 0 */ + + /* USER CODE END BusFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_BusFault_IRQn 0 */ + /* USER CODE END W1_BusFault_IRQn 0 */ + } +} + +/** + * @brief This function handles Undefined instruction or illegal state. + */ +void UsageFault_Handler(void) +{ + /* USER CODE BEGIN UsageFault_IRQn 0 */ + + /* USER CODE END UsageFault_IRQn 0 */ + while (1) + { + /* USER CODE BEGIN W1_UsageFault_IRQn 0 */ + /* USER CODE END W1_UsageFault_IRQn 0 */ + } +} + +/** + * @brief This function handles System service call via SWI instruction. + */ +void SVC_Handler(void) +{ + /* USER CODE BEGIN SVCall_IRQn 0 */ + + /* USER CODE END SVCall_IRQn 0 */ + /* USER CODE BEGIN SVCall_IRQn 1 */ + + /* USER CODE END SVCall_IRQn 1 */ +} + +/** + * @brief This function handles Debug monitor. + */ +void DebugMon_Handler(void) +{ + /* USER CODE BEGIN DebugMonitor_IRQn 0 */ + + /* USER CODE END DebugMonitor_IRQn 0 */ + /* USER CODE BEGIN DebugMonitor_IRQn 1 */ + + /* USER CODE END DebugMonitor_IRQn 1 */ +} + +/** + * @brief This function handles Pendable request for system service. + */ +void PendSV_Handler(void) +{ + /* USER CODE BEGIN PendSV_IRQn 0 */ + + /* USER CODE END PendSV_IRQn 0 */ + /* USER CODE BEGIN PendSV_IRQn 1 */ + + /* USER CODE END PendSV_IRQn 1 */ +} + +/** + * @brief This function handles System tick timer. + */ +void SysTick_Handler(void) +{ + /* USER CODE BEGIN SysTick_IRQn 0 */ + + /* USER CODE END SysTick_IRQn 0 */ + HAL_IncTick(); + /* USER CODE BEGIN SysTick_IRQn 1 */ + + /* USER CODE END SysTick_IRQn 1 */ +} + +/******************************************************************************/ +/* STM32L4xx Peripheral Interrupt Handlers */ +/* Add here the Interrupt Handlers for the used peripherals. */ +/* For the available peripheral interrupt handler names, */ +/* please refer to the startup file (startup_stm32l4xx.s). */ +/******************************************************************************/ + +/** + * @brief This function handles DMA1 channel1 global interrupt. + */ +void DMA1_Channel1_IRQHandler(void) +{ + /* USER CODE BEGIN DMA1_Channel1_IRQn 0 */ + + /* USER CODE END DMA1_Channel1_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_adc1); + /* USER CODE BEGIN DMA1_Channel1_IRQn 1 */ + + /* USER CODE END DMA1_Channel1_IRQn 1 */ +} + +/** + * @brief This function handles DMA1 channel4 global interrupt. + */ +void DMA1_Channel4_IRQHandler(void) +{ + /* USER CODE BEGIN DMA1_Channel4_IRQn 0 */ + + /* USER CODE END DMA1_Channel4_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_i2c2_tx); + /* USER CODE BEGIN DMA1_Channel4_IRQn 1 */ + + /* USER CODE END DMA1_Channel4_IRQn 1 */ +} + +/** + * @brief This function handles DMA1 channel5 global interrupt. + */ +void DMA1_Channel5_IRQHandler(void) +{ + /* USER CODE BEGIN DMA1_Channel5_IRQn 0 */ + + /* USER CODE END DMA1_Channel5_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_i2c2_rx); + /* USER CODE BEGIN DMA1_Channel5_IRQn 1 */ + + /* USER CODE END DMA1_Channel5_IRQn 1 */ +} + +/** + * @brief This function handles DMA1 channel6 global interrupt. + */ +void DMA1_Channel6_IRQHandler(void) +{ + /* USER CODE BEGIN DMA1_Channel6_IRQn 0 */ + + /* USER CODE END DMA1_Channel6_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_i2c1_tx); + /* USER CODE BEGIN DMA1_Channel6_IRQn 1 */ + + /* USER CODE END DMA1_Channel6_IRQn 1 */ +} + +/** + * @brief This function handles DMA1 channel7 global interrupt. + */ +void DMA1_Channel7_IRQHandler(void) +{ + /* USER CODE BEGIN DMA1_Channel7_IRQn 0 */ + + /* USER CODE END DMA1_Channel7_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_i2c1_rx); + /* USER CODE BEGIN DMA1_Channel7_IRQn 1 */ + + /* USER CODE END DMA1_Channel7_IRQn 1 */ +} + +/** + * @brief This function handles ADC1 global interrupt. + */ +void ADC1_IRQHandler(void) +{ + /* USER CODE BEGIN ADC1_IRQn 0 */ + + /* USER CODE END ADC1_IRQn 0 */ + HAL_ADC_IRQHandler(&hadc1); + /* USER CODE BEGIN ADC1_IRQn 1 */ + + /* USER CODE END ADC1_IRQn 1 */ +} + +/** + * @brief This function handles CAN1 TX interrupt. + */ +void CAN1_TX_IRQHandler(void) +{ + /* USER CODE BEGIN CAN1_TX_IRQn 0 */ + + /* USER CODE END CAN1_TX_IRQn 0 */ + HAL_CAN_IRQHandler(&hcan1); + /* USER CODE BEGIN CAN1_TX_IRQn 1 */ + + /* USER CODE END CAN1_TX_IRQn 1 */ +} + +/** + * @brief This function handles CAN1 RX0 interrupt. + */ +void CAN1_RX0_IRQHandler(void) +{ + /* USER CODE BEGIN CAN1_RX0_IRQn 0 */ + + /* USER CODE END CAN1_RX0_IRQn 0 */ + HAL_CAN_IRQHandler(&hcan1); + /* USER CODE BEGIN CAN1_RX0_IRQn 1 */ + + /* USER CODE END CAN1_RX0_IRQn 1 */ +} + +/** + * @brief This function handles TIM1 break interrupt and TIM15 global interrupt. + */ +void TIM1_BRK_TIM15_IRQHandler(void) +{ + /* USER CODE BEGIN TIM1_BRK_TIM15_IRQn 0 */ + + /* USER CODE END TIM1_BRK_TIM15_IRQn 0 */ + HAL_TIM_IRQHandler(&htim15); + /* USER CODE BEGIN TIM1_BRK_TIM15_IRQn 1 */ + + /* USER CODE END TIM1_BRK_TIM15_IRQn 1 */ +} + +/** + * @brief This function handles TIM1 update interrupt and TIM16 global interrupt. + */ +void TIM1_UP_TIM16_IRQHandler(void) +{ + /* USER CODE BEGIN TIM1_UP_TIM16_IRQn 0 */ + + /* USER CODE END TIM1_UP_TIM16_IRQn 0 */ + HAL_TIM_IRQHandler(&htim16); + /* USER CODE BEGIN TIM1_UP_TIM16_IRQn 1 */ + + /* USER CODE END TIM1_UP_TIM16_IRQn 1 */ +} + +/** + * @brief This function handles I2C1 event interrupt. + */ +void I2C1_EV_IRQHandler(void) +{ + /* USER CODE BEGIN I2C1_EV_IRQn 0 */ + + /* USER CODE END I2C1_EV_IRQn 0 */ + HAL_I2C_EV_IRQHandler(&hi2c1); + /* USER CODE BEGIN I2C1_EV_IRQn 1 */ + + /* USER CODE END I2C1_EV_IRQn 1 */ +} + +/** + * @brief This function handles I2C1 error interrupt. + */ +void I2C1_ER_IRQHandler(void) +{ + /* USER CODE BEGIN I2C1_ER_IRQn 0 */ + + /* USER CODE END I2C1_ER_IRQn 0 */ + HAL_I2C_ER_IRQHandler(&hi2c1); + /* USER CODE BEGIN I2C1_ER_IRQn 1 */ + + /* USER CODE END I2C1_ER_IRQn 1 */ +} + +/** + * @brief This function handles I2C2 event interrupt. + */ +void I2C2_EV_IRQHandler(void) +{ + /* USER CODE BEGIN I2C2_EV_IRQn 0 */ + + /* USER CODE END I2C2_EV_IRQn 0 */ + HAL_I2C_EV_IRQHandler(&hi2c2); + /* USER CODE BEGIN I2C2_EV_IRQn 1 */ + + /* USER CODE END I2C2_EV_IRQn 1 */ +} + +/** + * @brief This function handles I2C2 error interrupt. + */ +void I2C2_ER_IRQHandler(void) +{ + /* USER CODE BEGIN I2C2_ER_IRQn 0 */ + + /* USER CODE END I2C2_ER_IRQn 0 */ + HAL_I2C_ER_IRQHandler(&hi2c2); + /* USER CODE BEGIN I2C2_ER_IRQn 1 */ + + /* USER CODE END I2C2_ER_IRQn 1 */ +} + +/** + * @brief This function handles USART1 global interrupt. + */ +void USART1_IRQHandler(void) +{ + /* USER CODE BEGIN USART1_IRQn 0 */ + + /* USER CODE END USART1_IRQn 0 */ + HAL_UART_IRQHandler(&huart1); + /* USER CODE BEGIN USART1_IRQn 1 */ + + /* USER CODE END USART1_IRQn 1 */ +} + +/** + * @brief This function handles USART2 global interrupt. + */ +void USART2_IRQHandler(void) +{ + /* USER CODE BEGIN USART2_IRQn 0 */ + + /* USER CODE END USART2_IRQn 0 */ + HAL_UART_IRQHandler(&huart2); + /* USER CODE BEGIN USART2_IRQn 1 */ + + /* USER CODE END USART2_IRQn 1 */ +} + +/** + * @brief This function handles TIM6 global interrupt, DAC channel1 underrun error interrupt. + */ +void TIM6_DAC_IRQHandler(void) +{ + /* USER CODE BEGIN TIM6_DAC_IRQn 0 */ + + /* USER CODE END TIM6_DAC_IRQn 0 */ + HAL_TIM_IRQHandler(&htim6); + /* USER CODE BEGIN TIM6_DAC_IRQn 1 */ + + /* USER CODE END TIM6_DAC_IRQn 1 */ +} + +/** + * @brief This function handles DMA2 channel6 global interrupt. + */ +void DMA2_Channel6_IRQHandler(void) +{ + /* USER CODE BEGIN DMA2_Channel6_IRQn 0 */ + + /* USER CODE END DMA2_Channel6_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_usart1_tx); + /* USER CODE BEGIN DMA2_Channel6_IRQn 1 */ + + /* USER CODE END DMA2_Channel6_IRQn 1 */ +} + +/** + * @brief This function handles DMA2 channel7 global interrupt. + */ +void DMA2_Channel7_IRQHandler(void) +{ + /* USER CODE BEGIN DMA2_Channel7_IRQn 0 */ + + /* USER CODE END DMA2_Channel7_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_usart1_rx); + /* USER CODE BEGIN DMA2_Channel7_IRQn 1 */ + + /* USER CODE END DMA2_Channel7_IRQn 1 */ +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.system_stm32l4xx.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.system_stm32l4xx.c new file mode 100644 index 0000000000..26bd517974 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/removed.system_stm32l4xx.c @@ -0,0 +1,337 @@ +/** + ****************************************************************************** + * @file system_stm32l4xx.c + * @author MCD Application Team + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File + * + * This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32l4xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * After each device reset the MSI (4 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32l4xx.s" file, to + * configure the system clock before to branch to main program. + * + * This file configures the system clock as follows: + *============================================================================= + *----------------------------------------------------------------------------- + * System Clock source | MSI + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 4000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 4000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 1 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 1 + *----------------------------------------------------------------------------- + * PLL_M | 1 + *----------------------------------------------------------------------------- + * PLL_N | 8 + *----------------------------------------------------------------------------- + * PLL_P | 7 + *----------------------------------------------------------------------------- + * PLL_Q | 2 + *----------------------------------------------------------------------------- + * PLL_R | 2 + *----------------------------------------------------------------------------- + * PLLSAI1_P | NA + *----------------------------------------------------------------------------- + * PLLSAI1_Q | NA + *----------------------------------------------------------------------------- + * PLLSAI1_R | NA + *----------------------------------------------------------------------------- + * PLLSAI2_P | NA + *----------------------------------------------------------------------------- + * PLLSAI2_Q | NA + *----------------------------------------------------------------------------- + * PLLSAI2_R | NA + *----------------------------------------------------------------------------- + * Require 48MHz for USB OTG FS, | Disabled + * SDIO and RNG clock | + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32l4xx_system + * @{ + */ + +/** @addtogroup STM32L4xx_System_Private_Includes + * @{ + */ + +#include "stm32l4xx.h" + +#if !defined (HSE_VALUE) + #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (MSI_VALUE) + #define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/ +#endif /* MSI_VALUE */ + +#if !defined (HSI_VALUE) + #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_Defines + * @{ + */ + +/************************* Miscellaneous Configuration ************************/ +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ +/******************************************************************************/ +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_Variables + * @{ + */ + /* The SystemCoreClock variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetHCLKFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ + uint32_t SystemCoreClock = 4000000U; + + const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U}; + const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U}; + const uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \ + 4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U}; +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32L4xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system. + * @param None + * @retval None + */ + +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ + #endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set MSION bit */ + RCC->CR |= RCC_CR_MSION; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000U; + + /* Reset HSEON, CSSON , HSION, and PLLON bits */ + RCC->CR &= 0xEAF6FFFFU; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x00001000U; + + /* Reset HSEBYP bit */ + RCC->CR &= 0xFFFBFFFFU; + + /* Disable all interrupts */ + RCC->CIER = 0x00000000U; + + /* Configure the Vector Table location add offset address ------------------*/ +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is MSI, SystemCoreClock will contain the MSI_VALUE(*) + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***) + * or HSI_VALUE(*) or MSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) MSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value + * 4 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (***) HSE_VALUE is a constant defined in stm32l4xx_hal.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate(void) +{ + uint32_t tmp = 0U, msirange = 0U, pllvco = 0U, pllr = 2U, pllsource = 0U, pllm = 2U; + + /* Get MSI Range frequency--------------------------------------------------*/ + if((RCC->CR & RCC_CR_MSIRGSEL) == RESET) + { /* MSISRANGE from RCC_CSR applies */ + msirange = (RCC->CSR & RCC_CSR_MSISRANGE) >> 8U; + } + else + { /* MSIRANGE from RCC_CR applies */ + msirange = (RCC->CR & RCC_CR_MSIRANGE) >> 4U; + } + /*MSI frequency range in HZ*/ + msirange = MSIRangeTable[msirange]; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case 0x00: /* MSI used as system clock source */ + SystemCoreClock = msirange; + break; + + case 0x04: /* HSI used as system clock source */ + SystemCoreClock = HSI_VALUE; + break; + + case 0x08: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + + case 0x0C: /* PLL used as system clock source */ + /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN + SYSCLK = PLL_VCO / PLLR + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4U) + 1U ; + + switch (pllsource) + { + case 0x02: /* HSI used as PLL clock source */ + pllvco = (HSI_VALUE / pllm); + break; + + case 0x03: /* HSE used as PLL clock source */ + pllvco = (HSE_VALUE / pllm); + break; + + default: /* MSI used as PLL clock source */ + pllvco = (msirange / pllm); + break; + } + pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8U); + pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25U) + 1U) * 2U; + SystemCoreClock = pllvco/pllr; + break; + + default: + SystemCoreClock = msirange; + break; + } + /* Compute HCLK clock frequency --------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4U)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/rng.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/rng.c new file mode 100644 index 0000000000..6546613278 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/rng.c @@ -0,0 +1,96 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file rng.c + * @brief This file provides code for the configuration + * of the RNG instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "rng.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +RNG_HandleTypeDef hrng; + +/* RNG init function */ +void MX_RNG_Init(void) +{ + + /* USER CODE BEGIN RNG_Init 0 */ + + /* USER CODE END RNG_Init 0 */ + + /* USER CODE BEGIN RNG_Init 1 */ + + /* USER CODE END RNG_Init 1 */ + hrng.Instance = RNG; + if (HAL_RNG_Init(&hrng) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN RNG_Init 2 */ + + /* USER CODE END RNG_Init 2 */ + +} + +void HAL_RNG_MspInit(RNG_HandleTypeDef* rngHandle) +{ + + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + if(rngHandle->Instance==RNG) + { + /* USER CODE BEGIN RNG_MspInit 0 */ + + /* USER CODE END RNG_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_RNG; + PeriphClkInit.RngClockSelection = RCC_RNGCLKSOURCE_HSI48; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + /* RNG clock enable */ + __HAL_RCC_RNG_CLK_ENABLE(); + /* USER CODE BEGIN RNG_MspInit 1 */ + + /* USER CODE END RNG_MspInit 1 */ + } +} + +void HAL_RNG_MspDeInit(RNG_HandleTypeDef* rngHandle) +{ + + if(rngHandle->Instance==RNG) + { + /* USER CODE BEGIN RNG_MspDeInit 0 */ + + /* USER CODE END RNG_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_RNG_CLK_DISABLE(); + /* USER CODE BEGIN RNG_MspDeInit 1 */ + + /* USER CODE END RNG_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/stm32l4xx_hal_msp.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/stm32l4xx_hal_msp.c new file mode 100644 index 0000000000..1b68d600b9 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/stm32l4xx_hal_msp.c @@ -0,0 +1,81 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32l4xx_hal_msp.c + * @brief This file provides code for the MSP Initialization + * and de-Initialization codes. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Includes ------------------------------------------------------------------*/ +#include "main.h" +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Private typedef -----------------------------------------------------------*/ +/* USER CODE BEGIN TD */ + +/* USER CODE END TD */ + +/* Private define ------------------------------------------------------------*/ +/* USER CODE BEGIN Define */ + +/* USER CODE END Define */ + +/* Private macro -------------------------------------------------------------*/ +/* USER CODE BEGIN Macro */ + +/* USER CODE END Macro */ + +/* Private variables ---------------------------------------------------------*/ +/* USER CODE BEGIN PV */ + +/* USER CODE END PV */ + +/* Private function prototypes -----------------------------------------------*/ +/* USER CODE BEGIN PFP */ + +/* USER CODE END PFP */ + +/* External functions --------------------------------------------------------*/ +/* USER CODE BEGIN ExternalFunctions */ + +/* USER CODE END ExternalFunctions */ + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ +/** + * Initializes the Global MSP. + */ +void HAL_MspInit(void) +{ + /* USER CODE BEGIN MspInit 0 */ + + /* USER CODE END MspInit 0 */ + + __HAL_RCC_SYSCFG_CLK_ENABLE(); + __HAL_RCC_PWR_CLK_ENABLE(); + + /* System interrupt init*/ + + /* USER CODE BEGIN MspInit 1 */ + + /* USER CODE END MspInit 1 */ +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/tim.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/tim.c new file mode 100644 index 0000000000..9ef54dbe52 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/tim.c @@ -0,0 +1,236 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file tim.c + * @brief This file provides code for the configuration + * of the TIM instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "tim.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +TIM_HandleTypeDef htim6; +TIM_HandleTypeDef htim15; +TIM_HandleTypeDef htim16; + +/* TIM6 init function */ +void MX_TIM6_Init(void) +{ + + /* USER CODE BEGIN TIM6_Init 0 */ + + /* USER CODE END TIM6_Init 0 */ + + TIM_MasterConfigTypeDef sMasterConfig = {0}; + + /* USER CODE BEGIN TIM6_Init 1 */ + + /* USER CODE END TIM6_Init 1 */ + htim6.Instance = TIM6; + htim6.Init.Prescaler = 1600; + htim6.Init.CounterMode = TIM_COUNTERMODE_UP; + htim6.Init.Period = 1; + htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim6) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM6_Init 2 */ + + /* USER CODE END TIM6_Init 2 */ + +} +/* TIM15 init function */ +void MX_TIM15_Init(void) +{ + + /* USER CODE BEGIN TIM15_Init 0 */ + + /* USER CODE END TIM15_Init 0 */ + + TIM_MasterConfigTypeDef sMasterConfig = {0}; + + /* USER CODE BEGIN TIM15_Init 1 */ + + /* USER CODE END TIM15_Init 1 */ + htim15.Instance = TIM15; + htim15.Init.Prescaler = 1600; + htim15.Init.CounterMode = TIM_COUNTERMODE_UP; + htim15.Init.Period = 200; + htim15.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim15.Init.RepetitionCounter = 0; + htim15.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_OnePulse_Init(&htim15, TIM_OPMODE_SINGLE) != HAL_OK) + { + Error_Handler(); + } + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim15, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM15_Init 2 */ + + /* USER CODE END TIM15_Init 2 */ + +} +/* TIM16 init function */ +void MX_TIM16_Init(void) +{ + + /* USER CODE BEGIN TIM16_Init 0 */ + + /* USER CODE END TIM16_Init 0 */ + + /* USER CODE BEGIN TIM16_Init 1 */ + + /* USER CODE END TIM16_Init 1 */ + htim16.Instance = TIM16; + htim16.Init.Prescaler = 1600; + htim16.Init.CounterMode = TIM_COUNTERMODE_UP; + htim16.Init.Period = 10000; + htim16.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim16.Init.RepetitionCounter = 0; + htim16.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + if (HAL_TIM_Base_Init(&htim16) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN TIM16_Init 2 */ + + /* USER CODE END TIM16_Init 2 */ + +} + +void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle) +{ + + if(tim_baseHandle->Instance==TIM6) + { + /* USER CODE BEGIN TIM6_MspInit 0 */ + + /* USER CODE END TIM6_MspInit 0 */ + /* TIM6 clock enable */ + __HAL_RCC_TIM6_CLK_ENABLE(); + + /* TIM6 interrupt Init */ + HAL_NVIC_SetPriority(TIM6_DAC_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); + /* USER CODE BEGIN TIM6_MspInit 1 */ + + /* USER CODE END TIM6_MspInit 1 */ + } + else if(tim_baseHandle->Instance==TIM16) + { + /* USER CODE BEGIN TIM16_MspInit 0 */ + + /* USER CODE END TIM16_MspInit 0 */ + /* TIM16 clock enable */ + __HAL_RCC_TIM16_CLK_ENABLE(); + + /* TIM16 interrupt Init */ + HAL_NVIC_SetPriority(TIM1_UP_TIM16_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(TIM1_UP_TIM16_IRQn); + /* USER CODE BEGIN TIM16_MspInit 1 */ + + /* USER CODE END TIM16_MspInit 1 */ + } +} + +void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef* tim_onepulseHandle) +{ + + if(tim_onepulseHandle->Instance==TIM15) + { + /* USER CODE BEGIN TIM15_MspInit 0 */ + + /* USER CODE END TIM15_MspInit 0 */ + /* TIM15 clock enable */ + __HAL_RCC_TIM15_CLK_ENABLE(); + + /* TIM15 interrupt Init */ + HAL_NVIC_SetPriority(TIM1_BRK_TIM15_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(TIM1_BRK_TIM15_IRQn); + /* USER CODE BEGIN TIM15_MspInit 1 */ + + /* USER CODE END TIM15_MspInit 1 */ + } +} + +void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle) +{ + + if(tim_baseHandle->Instance==TIM6) + { + /* USER CODE BEGIN TIM6_MspDeInit 0 */ + + /* USER CODE END TIM6_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM6_CLK_DISABLE(); + + /* TIM6 interrupt Deinit */ + HAL_NVIC_DisableIRQ(TIM6_DAC_IRQn); + /* USER CODE BEGIN TIM6_MspDeInit 1 */ + + /* USER CODE END TIM6_MspDeInit 1 */ + } + else if(tim_baseHandle->Instance==TIM16) + { + /* USER CODE BEGIN TIM16_MspDeInit 0 */ + + /* USER CODE END TIM16_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM16_CLK_DISABLE(); + + /* TIM16 interrupt Deinit */ + HAL_NVIC_DisableIRQ(TIM1_UP_TIM16_IRQn); + /* USER CODE BEGIN TIM16_MspDeInit 1 */ + + /* USER CODE END TIM16_MspDeInit 1 */ + } +} + +void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef* tim_onepulseHandle) +{ + + if(tim_onepulseHandle->Instance==TIM15) + { + /* USER CODE BEGIN TIM15_MspDeInit 0 */ + + /* USER CODE END TIM15_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM15_CLK_DISABLE(); + + /* TIM15 interrupt Deinit */ + HAL_NVIC_DisableIRQ(TIM1_BRK_TIM15_IRQn); + /* USER CODE BEGIN TIM15_MspDeInit 1 */ + + /* USER CODE END TIM15_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/usart.c b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/usart.c new file mode 100644 index 0000000000..f6c0b92e72 --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/board/strain2c/v1B0/src/usart.c @@ -0,0 +1,262 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file usart.c + * @brief This file provides code for the configuration + * of the USART instances. + ****************************************************************************** + * @attention + * + * Copyright (c) 2022 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ +/* Includes ------------------------------------------------------------------*/ +#include "usart.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +UART_HandleTypeDef huart1; +UART_HandleTypeDef huart2; +DMA_HandleTypeDef hdma_usart1_tx; +DMA_HandleTypeDef hdma_usart1_rx; + +/* USART1 init function */ + +void MX_USART1_UART_Init(void) +{ + + /* USER CODE BEGIN USART1_Init 0 */ + + /* USER CODE END USART1_Init 0 */ + + /* USER CODE BEGIN USART1_Init 1 */ + + /* USER CODE END USART1_Init 1 */ + huart1.Instance = USART1; + huart1.Init.BaudRate = 115200; + huart1.Init.WordLength = UART_WORDLENGTH_8B; + huart1.Init.StopBits = UART_STOPBITS_1; + huart1.Init.Parity = UART_PARITY_NONE; + huart1.Init.Mode = UART_MODE_TX_RX; + huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE; + huart1.Init.OverSampling = UART_OVERSAMPLING_16; + huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; + huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; + if (HAL_UART_Init(&huart1) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN USART1_Init 2 */ + + /* USER CODE END USART1_Init 2 */ + +} +/* USART2 init function */ + +void MX_USART2_UART_Init(void) +{ + + /* USER CODE BEGIN USART2_Init 0 */ + + /* USER CODE END USART2_Init 0 */ + + /* USER CODE BEGIN USART2_Init 1 */ + + /* USER CODE END USART2_Init 1 */ + huart2.Instance = USART2; + huart2.Init.BaudRate = 115200; + huart2.Init.WordLength = UART_WORDLENGTH_8B; + huart2.Init.StopBits = UART_STOPBITS_1; + huart2.Init.Parity = UART_PARITY_NONE; + huart2.Init.Mode = UART_MODE_TX_RX; + huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE; + huart2.Init.OverSampling = UART_OVERSAMPLING_16; + huart2.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; + huart2.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; + if (HAL_UART_Init(&huart2) != HAL_OK) + { + Error_Handler(); + } + /* USER CODE BEGIN USART2_Init 2 */ + + /* USER CODE END USART2_Init 2 */ + +} + +void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle) +{ + + GPIO_InitTypeDef GPIO_InitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + if(uartHandle->Instance==USART1) + { + /* USER CODE BEGIN USART1_MspInit 0 */ + + /* USER CODE END USART1_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1; + PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + /* USART1 clock enable */ + __HAL_RCC_USART1_CLK_ENABLE(); + + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**USART1 GPIO Configuration + PA10 ------> USART1_RX + PA9 ------> USART1_TX + */ + GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF7_USART1; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* USART1 DMA Init */ + /* USART1_TX Init */ + hdma_usart1_tx.Instance = DMA2_Channel6; + hdma_usart1_tx.Init.Request = DMA_REQUEST_2; + hdma_usart1_tx.Init.Direction = DMA_MEMORY_TO_PERIPH; + hdma_usart1_tx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_usart1_tx.Init.MemInc = DMA_MINC_ENABLE; + hdma_usart1_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_usart1_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_usart1_tx.Init.Mode = DMA_NORMAL; + hdma_usart1_tx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_usart1_tx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(uartHandle,hdmatx,hdma_usart1_tx); + + /* USART1_RX Init */ + hdma_usart1_rx.Instance = DMA2_Channel7; + hdma_usart1_rx.Init.Request = DMA_REQUEST_2; + hdma_usart1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_usart1_rx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_usart1_rx.Init.MemInc = DMA_MINC_ENABLE; + hdma_usart1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_usart1_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_usart1_rx.Init.Mode = DMA_NORMAL; + hdma_usart1_rx.Init.Priority = DMA_PRIORITY_LOW; + if (HAL_DMA_Init(&hdma_usart1_rx) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(uartHandle,hdmarx,hdma_usart1_rx); + + /* USART1 interrupt Init */ + HAL_NVIC_SetPriority(USART1_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(USART1_IRQn); + /* USER CODE BEGIN USART1_MspInit 1 */ + + /* USER CODE END USART1_MspInit 1 */ + } + else if(uartHandle->Instance==USART2) + { + /* USER CODE BEGIN USART2_MspInit 0 */ + + /* USER CODE END USART2_MspInit 0 */ + + /** Initializes the peripherals clock + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2; + PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } + + /* USART2 clock enable */ + __HAL_RCC_USART2_CLK_ENABLE(); + + __HAL_RCC_GPIOA_CLK_ENABLE(); + /**USART2 GPIO Configuration + PA2 ------> USART2_TX + PA3 ------> USART2_RX + */ + GPIO_InitStruct.Pin = GPIO_PIN_2|GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF7_USART2; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* USART2 interrupt Init */ + HAL_NVIC_SetPriority(USART2_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(USART2_IRQn); + /* USER CODE BEGIN USART2_MspInit 1 */ + + /* USER CODE END USART2_MspInit 1 */ + } +} + +void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle) +{ + + if(uartHandle->Instance==USART1) + { + /* USER CODE BEGIN USART1_MspDeInit 0 */ + + /* USER CODE END USART1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_USART1_CLK_DISABLE(); + + /**USART1 GPIO Configuration + PA10 ------> USART1_RX + PA9 ------> USART1_TX + */ + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_10|GPIO_PIN_9); + + /* USART1 DMA DeInit */ + HAL_DMA_DeInit(uartHandle->hdmatx); + HAL_DMA_DeInit(uartHandle->hdmarx); + + /* USART1 interrupt Deinit */ + HAL_NVIC_DisableIRQ(USART1_IRQn); + /* USER CODE BEGIN USART1_MspDeInit 1 */ + + /* USER CODE END USART1_MspDeInit 1 */ + } + else if(uartHandle->Instance==USART2) + { + /* USER CODE BEGIN USART2_MspDeInit 0 */ + + /* USER CODE END USART2_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_USART2_CLK_DISABLE(); + + /**USART2 GPIO Configuration + PA2 ------> USART2_TX + PA3 ------> USART2_RX + */ + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_2|GPIO_PIN_3); + + /* USART2 interrupt Deinit */ + HAL_NVIC_DisableIRQ(USART2_IRQn); + /* USER CODE BEGIN USART2_MspDeInit 1 */ + + /* USER CODE END USART2_MspDeInit 1 */ + } +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg.h index 89dd05511d..4720f764af 100644 --- a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg.h +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg.h @@ -208,6 +208,16 @@ extern "C" { #error unknown driver version #endif +#elif defined(STM32HAL_BOARD_STRAIN2C) + + #if (STM32HAL_DRIVER_VERSION == 0x1B0) + #include "../src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h" + // we also need some ll includes contained in the driver section + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_ll_gpio.h" + #else + #error unknown driver version + #endif + #else #error pls define a STM32HAL_BOARD_${BRD} diff --git a/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h new file mode 100644 index 0000000000..5fa0989c8d --- /dev/null +++ b/emBODY/eBcode/arch-arm/libs/lowlevel/stm32hal/src/config/stm32hal_driver_cfg_of_strain2c_v1B0.h @@ -0,0 +1,533 @@ +/* + * Copyright (C) 2018 iCub Facility - Istituto Italiano di Tecnologia + * Author: Marco Accame + * email: marco.accame@iit.it + * website: www.robotcub.org + * Permission is granted to copy, distribute, and/or modify this program + * under the terms of the GNU General Public License, version 2 or any + * later version published by the Free Software Foundation. + * + * A copy of the license can be found at + * http://www.robotcub.org/icub/license/gpl.txt + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details +*/ + +// - include guard ---------------------------------------------------------------------------------------------------- + +#ifndef __STM32HAL_DRIVER_CFG_OF_STRAIN2C_V1B0_H_ +#define __STM32HAL_DRIVER_CFG_OF_STRAIN2C_V1B0_H_ + + +#if !defined(USE_STM32HAL) + #error USE_STM32HAL must be defined +#endif + + +#if !defined(STM32HAL_BOARD_STRAIN2C) + #error STM32HAL_BOARD_STRAIN2C must be defined +#endif + + +// TODO: +// add the file stm32l4xx_hal_conf.h which cubemx has generated in here. +// only things: +// 1. change the prefix folder of include of main.h (if present) +// considering stm32hal/api as the starting point. +// so for instance: #include "../src/board/${brd}/inc/main.h" +// 2. change the prefix folder of include files of the driver by +// considering stm32hal/api as the starting point. +// so, for instance: ../src/driver/${drivername}/inc/stm32l4xx_hal_rcc.h + + +// insert between here and include-guard + +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32l4xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32l4xx_hal_conf.h. + ****************************************************************************** + * @attention + * + * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32L4xx_HAL_CONF_H +#define STM32L4xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +/*#define HAL_CRYP_MODULE_ENABLED */ +#define HAL_CAN_MODULE_ENABLED +/*#define HAL_COMP_MODULE_ENABLED */ +/*#define HAL_CRC_MODULE_ENABLED */ +/*#define HAL_CRYP_MODULE_ENABLED */ +/*#define HAL_DAC_MODULE_ENABLED */ +/*#define HAL_DCMI_MODULE_ENABLED */ +/*#define HAL_DMA2D_MODULE_ENABLED */ +/*#define HAL_DFSDM_MODULE_ENABLED */ +/*#define HAL_DSI_MODULE_ENABLED */ +/*#define HAL_FIREWALL_MODULE_ENABLED */ +/*#define HAL_GFXMMU_MODULE_ENABLED */ +/*#define HAL_HCD_MODULE_ENABLED */ +/*#define HAL_HASH_MODULE_ENABLED */ +/*#define HAL_I2S_MODULE_ENABLED */ +/*#define HAL_IRDA_MODULE_ENABLED */ +/*#define HAL_IWDG_MODULE_ENABLED */ +/*#define HAL_LTDC_MODULE_ENABLED */ +/*#define HAL_LCD_MODULE_ENABLED */ +/*#define HAL_LPTIM_MODULE_ENABLED */ +/*#define HAL_MMC_MODULE_ENABLED */ +/*#define HAL_NAND_MODULE_ENABLED */ +/*#define HAL_NOR_MODULE_ENABLED */ +/*#define HAL_OPAMP_MODULE_ENABLED */ +/*#define HAL_OSPI_MODULE_ENABLED */ +/*#define HAL_OSPI_MODULE_ENABLED */ +/*#define HAL_PCD_MODULE_ENABLED */ +/*#define HAL_PKA_MODULE_ENABLED */ +/*#define HAL_QSPI_MODULE_ENABLED */ +/*#define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RNG_MODULE_ENABLED +/*#define HAL_RTC_MODULE_ENABLED */ +/*#define HAL_SAI_MODULE_ENABLED */ +/*#define HAL_SD_MODULE_ENABLED */ +/*#define HAL_SMBUS_MODULE_ENABLED */ +/*#define HAL_SMARTCARD_MODULE_ENABLED */ +/*#define HAL_SPI_MODULE_ENABLED */ +/*#define HAL_SRAM_MODULE_ENABLED */ +/*#define HAL_SWPMI_MODULE_ENABLED */ +#define HAL_TIM_MODULE_ENABLED +/*#define HAL_TSC_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/*#define HAL_USART_MODULE_ENABLED */ +/*#define HAL_WWDG_MODULE_ENABLED */ +/*#define HAL_EXTI_MODULE_ENABLED */ +/*#define HAL_PSSI_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)10000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal Multiple Speed oscillator (MSI) default value. + * This value is the default MSI range value after Reset. + */ +#if !defined (MSI_VALUE) + #define MSI_VALUE ((uint32_t)4000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* MSI_VALUE */ +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG. + * This internal oscillator is mainly dedicated to provide a high precision clock to + * the USB peripheral by means of a special Clock Recovery System (CRS) circuitry. + * When the CRS is not used, the HSI48 RC oscillator runs on it default frequency + * which is subject to manufacturing process variations. + */ +#if !defined (HSI48_VALUE) + #define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz. + The real value my vary depending on manufacturing process variations.*/ +#endif /* HSI48_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature.*/ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE 32768U /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for SAI1 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI1_CLOCK_VALUE) + #define EXTERNAL_SAI1_CLOCK_VALUE 2097000U /*!< Value of the SAI1 External clock source in Hz*/ +#endif /* EXTERNAL_SAI1_CLOCK_VALUE */ + +/** + * @brief External clock source for SAI2 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI2_CLOCK_VALUE) + #define EXTERNAL_SAI2_CLOCK_VALUE 48000U /*!< Value of the SAI2 External clock source in Hz*/ +#endif /* EXTERNAL_SAI2_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ + +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 0U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_ENABLE 1U + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ + //#define USE_FULL_ASSERT 1U + +/* ################## Register callback feature configuration ############### */ +/** + * @brief Set below the peripheral configuration to "1U" to add the support + * of HAL callback registration/deregistration feature for the HAL + * driver(s). This allows user application to provide specific callback + * functions thanks to HAL_PPP_RegisterCallback() rather than overwriting + * the default weak callback functions (see each stm32l4xx_hal_ppp.h file + * for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef + * for each PPP peripheral). + */ +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U +//#define USE_HAL_CAN_REGISTER_CALLBACKS 1U +#define USE_HAL_COMP_REGISTER_CALLBACKS 0U +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U +#define USE_HAL_GFXMMU_REGISTER_CALLBACKS 0U +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U +#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U +#define USE_HAL_OSPI_REGISTER_CALLBACKS 0U +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U +#define USE_HAL_SD_REGISTER_CALLBACKS 0U +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U +#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U +#define USE_HAL_TSC_REGISTER_CALLBACKS 0U +#define USE_HAL_UART_REGISTER_CALLBACKS 0U +#define USE_HAL_USART_REGISTER_CALLBACKS 0U +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver + * Activated: CRC code is present inside driver + * Deactivated: CRC code cleaned from driver + */ + +#define USE_SPI_CRC 0U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32l4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_GFXMMU_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_gfxmmu.h" +#endif /* HAL_GFXMMU_MODULE_ENABLED */ + +#ifdef HAL_FIREWALL_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_firewall.h" +#endif /* HAL_FIREWALL_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LCD_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_lcd.h" +#endif /* HAL_LCD_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_OSPI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_ospi.h" +#endif /* HAL_OSPI_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_PKA_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_pka.h" +#endif /* HAL_PKA_MODULE_ENABLED */ + +#ifdef HAL_PSSI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_pssi.h" +#endif /* HAL_PSSI_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_TSC_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_tsc.h" +#endif /* HAL_TSC_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "../src/driver/stm32l4-v1B0/inc/stm32l4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t *file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32L4xx_HAL_CONF_H */ + + +#endif // include-guard of +