From 7142b86cabe5b643fac0f9941b21bdba8fcfd416 Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 13:51:12 +1100 Subject: [PATCH 001/212] * feat: added target for AIKONF7 --- CMakeLists.txt | 99 +-------------------- src/main/target/AIKONF7/target.c | 60 +++++++++++++ src/main/target/AIKONF7/target.h | 144 +++++++++++++++++++++++++++++++ 3 files changed, 205 insertions(+), 98 deletions(-) create mode 100644 src/main/target/AIKONF7/target.c create mode 100644 src/main/target/AIKONF7/target.h diff --git a/CMakeLists.txt b/CMakeLists.txt index db8ec36897b..86c842526d6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,98 +1 @@ -cmake_minimum_required(VERSION 3.13...3.18) - -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") - -set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") -set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") -set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") -set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") -set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") -set(DOWNLOADS_DIR "${MAIN_DIR}/downloads") -set(TOOLS_DIR "${MAIN_DIR}/tools") - -option(SITL "SITL build for host system" OFF) - -set(TOOLCHAIN_OPTIONS none arm-none-eabi host) -if (SITL) - if (CMAKE_HOST_APPLE) - set(MACOSX TRUE) - endif() - set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") -else() - set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") -endif() - -set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) -if("" STREQUAL TOOLCHAIN) - set(TOOLCHAIN none) -endif() -if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS) - message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}. Valid options are: ${TOOLCHAIN_OPTIONS}") -endif() - -option(COMPILER_VERSION_CHECK "Ensure the compiler matches the expected version" ON) - -include(GetGitRevisionDescription) -get_git_head_revision(GIT_REFSPEC GIT_SHA1) -string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV) - -# Load settings related functions, so the tests can use them -include(main) -include(settings) - -if(TOOLCHAIN STREQUAL none) - add_subdirectory(src/test) -else() - if (SITL) - include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") - else() - set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") - include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") - endif() -endif() - -project(INAV VERSION 8.0.0) - -enable_language(ASM) - -if(MACOSX AND SITL) - set(CMAKE_C_STANDARD 11) -else() - set(CMAKE_C_STANDARD 99) -endif() -set(CMAKE_C_EXTENSIONS ON) -set(CMAKE_C_STANDARD_REQUIRED ON) -set(CMAKE_CXX_STANDARD 11) -set(CMAKE_CXX_EXTENSIONS ON) -set(CMAKE_CXX_STANDARD_REQUIRED ON) - -if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") - set(IS_RELEASE_BUILD ON) -endif() - -set(FIRMWARE_VERSION ${PROJECT_VERSION}) - -option(WARNINGS_AS_ERRORS "Make all warnings into errors") -message("-- toolchain: ${TOOLCHAIN}, WARNINGS_AS_ERRORS: ${WARNINGS_AS_ERRORS}") - -set(COMMON_COMPILE_DEFINITIONS - FC_VERSION_MAJOR=${CMAKE_PROJECT_VERSION_MAJOR} - FC_VERSION_MINOR=${CMAKE_PROJECT_VERSION_MINOR} - FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH} -) - -if (NOT SITL) - include(openocd) - include(svd) -endif() - -include(stm32) -include(at32) -include(sitl) - -add_subdirectory(src) - -collect_targets() - -message("-- Build type: ${CMAKE_BUILD_TYPE}") -include(ci) +target_stm32f722xe(AIKONF7 SKIP_RELEASES) diff --git a/src/main/target/AIKONF7/target.c b/src/main/target/AIKONF7/target.c new file mode 100644 index 00000000000..7f5d8453e14 --- /dev/null +++ b/src/main/target/AIKONF7/target.c @@ -0,0 +1,60 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + * + * This target has been autgenerated by bf2inav.py + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +//#include "drivers/sensor.h" + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM10, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h new file mode 100644 index 00000000000..4fe95d6c4dc --- /dev/null +++ b/src/main/target/AIKONF7/target.h @@ -0,0 +1,144 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + * + * This target has been autgenerated by bf2inav.py + */ + +#pragma once + +//#define USE_TARGET_CONFIG + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY ) + + + +#define TARGET_BOARD_IDENTIFIER "RPTY" +#define USBD_PRODUCT_STRING "AIKONF7" +// Beeper +#define USE_BEEPER +#define BEEPER PC15 +#define BEEPER_INVERTED +// Leds +#define USE_LED_STRIP +#define WS2811_PIN PA15 +#define LED0 PC13 +// UARTs +#define USB_IO +#define USE_VCP +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 +#define SERIAL_PORT_COUNT 5 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +// SPI +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA7 +#define SPI1_MOSI_PIN PA6 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB15 +#define SPI2_MOSI_PIN PC2 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB5 +#define SPI3_MOSI_PIN PB4 +// I2C +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +// ADC +#define ADC_CHANNEL_1_PIN PC0 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define ADC_CHANNEL_2_PIN PC1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define ADC_CHANNEL_3_PIN PC3 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define USE_ADC +#define ADC_INSTANCE ADC1 +// Gyro & ACC +#define USE_IMU_BMI270 +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_BUS BUS_SPI1 +#define IMU_BMI270_ALIGN CW0_DEG +#define USE_IMU_MPU6000 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 +#define IMU_MPU6000_ALIGN CW0_DEG +// BARO +#define USE_BARO +#define USE_BARO_ALL +#define USE_BARO_SPI_BMP280 +#define BMP280_SPI_BUS BUS_SPI3 +#define BMP280_CS_PIN PB2 +// OSD +#define USE_MAX7456 +#define MAX7456_CS_PIN PB12 +#define MAX7456_SPI_BUS BUS_SPI2 +// Blackbox +#define USE_FLASHFS +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PB0 +#define USE_FLASH_W25M +#define W25M_SPI_BUS BUS_SPI3 +#define W25M_CS_PIN PB0 +#define USE_FLASH_W25M02G +#define W25M02G_SPI_BUS BUS_SPI3 +#define W25M02G_CS_PIN PB0 +#define USE_FLASH_W25M512 +#define W25M512_SPI_BUS BUS_SPI3 +#define W25M512_CS_PIN PB0 +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN PB0 + +// PINIO + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC14 + + +// Others + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define USE_DSHOT +#define USE_ESC_SENSOR + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff From d8cb89ec96e0c8f1c54c927f11a8d8cab3db5c3f Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 15:25:24 +1100 Subject: [PATCH 002/212] * fix: corrected some implementation mistakes --- CMakeLists.txt | 99 +++++++++++++++++++++++++- src/main/target/AIKONF7/CMakeLists.txt | 1 + 2 files changed, 99 insertions(+), 1 deletion(-) create mode 100644 src/main/target/AIKONF7/CMakeLists.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index 86c842526d6..db8ec36897b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1 +1,98 @@ -target_stm32f722xe(AIKONF7 SKIP_RELEASES) +cmake_minimum_required(VERSION 3.13...3.18) + +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") + +set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") +set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") +set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") +set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") +set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") +set(DOWNLOADS_DIR "${MAIN_DIR}/downloads") +set(TOOLS_DIR "${MAIN_DIR}/tools") + +option(SITL "SITL build for host system" OFF) + +set(TOOLCHAIN_OPTIONS none arm-none-eabi host) +if (SITL) + if (CMAKE_HOST_APPLE) + set(MACOSX TRUE) + endif() + set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +else() + set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +endif() + +set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) +if("" STREQUAL TOOLCHAIN) + set(TOOLCHAIN none) +endif() +if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS) + message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}. Valid options are: ${TOOLCHAIN_OPTIONS}") +endif() + +option(COMPILER_VERSION_CHECK "Ensure the compiler matches the expected version" ON) + +include(GetGitRevisionDescription) +get_git_head_revision(GIT_REFSPEC GIT_SHA1) +string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV) + +# Load settings related functions, so the tests can use them +include(main) +include(settings) + +if(TOOLCHAIN STREQUAL none) + add_subdirectory(src/test) +else() + if (SITL) + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + else() + set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") + endif() +endif() + +project(INAV VERSION 8.0.0) + +enable_language(ASM) + +if(MACOSX AND SITL) + set(CMAKE_C_STANDARD 11) +else() + set(CMAKE_C_STANDARD 99) +endif() +set(CMAKE_C_EXTENSIONS ON) +set(CMAKE_C_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_EXTENSIONS ON) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") + set(IS_RELEASE_BUILD ON) +endif() + +set(FIRMWARE_VERSION ${PROJECT_VERSION}) + +option(WARNINGS_AS_ERRORS "Make all warnings into errors") +message("-- toolchain: ${TOOLCHAIN}, WARNINGS_AS_ERRORS: ${WARNINGS_AS_ERRORS}") + +set(COMMON_COMPILE_DEFINITIONS + FC_VERSION_MAJOR=${CMAKE_PROJECT_VERSION_MAJOR} + FC_VERSION_MINOR=${CMAKE_PROJECT_VERSION_MINOR} + FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH} +) + +if (NOT SITL) + include(openocd) + include(svd) +endif() + +include(stm32) +include(at32) +include(sitl) + +add_subdirectory(src) + +collect_targets() + +message("-- Build type: ${CMAKE_BUILD_TYPE}") +include(ci) diff --git a/src/main/target/AIKONF7/CMakeLists.txt b/src/main/target/AIKONF7/CMakeLists.txt new file mode 100644 index 00000000000..86c842526d6 --- /dev/null +++ b/src/main/target/AIKONF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(AIKONF7 SKIP_RELEASES) From a00ca08263644cef3cfb9523ddf2fc53bee98427 Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 15:49:06 +1100 Subject: [PATCH 003/212] * fix: tweaked weird baro line --- src/main/target/AIKONF7/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h index 4fe95d6c4dc..4ad9da0ac13 100644 --- a/src/main/target/AIKONF7/target.h +++ b/src/main/target/AIKONF7/target.h @@ -95,7 +95,7 @@ #define IMU_MPU6000_ALIGN CW0_DEG // BARO #define USE_BARO -#define USE_BARO_ALL +// #define USE_BARO_ALL #define USE_BARO_SPI_BMP280 #define BMP280_SPI_BUS BUS_SPI3 #define BMP280_CS_PIN PB2 From 227ccea5cec31f71044b7bfc1e2f1d858b270e5d Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 15:56:50 +1100 Subject: [PATCH 004/212] * fix: disabled baro, not even present on V2 board anyway --- src/main/target/AIKONF7/target.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h index 4ad9da0ac13..350b2142ba6 100644 --- a/src/main/target/AIKONF7/target.h +++ b/src/main/target/AIKONF7/target.h @@ -94,11 +94,11 @@ #define MPU6000_SPI_BUS BUS_SPI1 #define IMU_MPU6000_ALIGN CW0_DEG // BARO -#define USE_BARO +// #define USE_BARO // #define USE_BARO_ALL -#define USE_BARO_SPI_BMP280 -#define BMP280_SPI_BUS BUS_SPI3 -#define BMP280_CS_PIN PB2 +// #define USE_BARO_SPI_BMP280 +// #define BMP280_SPI_BUS BUS_SPI3 +// #define BMP280_CS_PIN PB2 // OSD #define USE_MAX7456 #define MAX7456_CS_PIN PB12 From 9afb38db35185bf15320eb1dc971e93b9c600abc Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 16:08:17 +1100 Subject: [PATCH 005/212] * fix: maybe misconfigured the baro lets try this way --- src/main/target/AIKONF7/target.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h index 350b2142ba6..bf9079e2dbd 100644 --- a/src/main/target/AIKONF7/target.h +++ b/src/main/target/AIKONF7/target.h @@ -94,11 +94,11 @@ #define MPU6000_SPI_BUS BUS_SPI1 #define IMU_MPU6000_ALIGN CW0_DEG // BARO -// #define USE_BARO -// #define USE_BARO_ALL -// #define USE_BARO_SPI_BMP280 -// #define BMP280_SPI_BUS BUS_SPI3 -// #define BMP280_CS_PIN PB2 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define BMP280_SPI_BUS BUS_SPI3 +#define BMP280_CS_PIN PB2 // OSD #define USE_MAX7456 #define MAX7456_CS_PIN PB12 From a7458d15ef93593bc7c4440dc52160d4a678b5ad Mon Sep 17 00:00:00 2001 From: Max Bainrot Date: Fri, 29 Dec 2023 16:49:44 +1100 Subject: [PATCH 006/212] * fix: fixed missing serial port --- src/main/target/AIKONF7/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/AIKONF7/target.h b/src/main/target/AIKONF7/target.h index bf9079e2dbd..f738d688a88 100644 --- a/src/main/target/AIKONF7/target.h +++ b/src/main/target/AIKONF7/target.h @@ -53,7 +53,7 @@ #define USE_UART5 #define UART5_RX_PIN PD2 #define UART5_TX_PIN PC12 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 6 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_CRSF // SPI From f2f872c64ef1e54053c0f8461b41bcbd4bf6e8d4 Mon Sep 17 00:00:00 2001 From: jamming Date: Tue, 11 Jun 2024 13:40:18 +0800 Subject: [PATCH 007/212] Add a new target KakuteF4wing --- src/main/target/KAKUTEF4WING/CMakeLists.txt | 1 + src/main/target/KAKUTEF4WING/config.c | 42 ++++ src/main/target/KAKUTEF4WING/hardware_setup.c | 42 ++++ src/main/target/KAKUTEF4WING/target.c | 42 ++++ src/main/target/KAKUTEF4WING/target.h | 184 ++++++++++++++++++ 5 files changed, 311 insertions(+) create mode 100644 src/main/target/KAKUTEF4WING/CMakeLists.txt create mode 100755 src/main/target/KAKUTEF4WING/config.c create mode 100644 src/main/target/KAKUTEF4WING/hardware_setup.c create mode 100755 src/main/target/KAKUTEF4WING/target.c create mode 100644 src/main/target/KAKUTEF4WING/target.h diff --git a/src/main/target/KAKUTEF4WING/CMakeLists.txt b/src/main/target/KAKUTEF4WING/CMakeLists.txt new file mode 100644 index 00000000000..bf96ecb5d3b --- /dev/null +++ b/src/main/target/KAKUTEF4WING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(KAKUTEF4WING) diff --git a/src/main/target/KAKUTEF4WING/config.c b/src/main/target/KAKUTEF4WING/config.c new file mode 100755 index 00000000000..206221e9930 --- /dev/null +++ b/src/main/target/KAKUTEF4WING/config.c @@ -0,0 +1,42 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "rx/rx.h" + +#include "io/piniobox.h" +#include "drivers/serial.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} + diff --git a/src/main/target/KAKUTEF4WING/hardware_setup.c b/src/main/target/KAKUTEF4WING/hardware_setup.c new file mode 100644 index 00000000000..f78fd65cd4c --- /dev/null +++ b/src/main/target/KAKUTEF4WING/hardware_setup.c @@ -0,0 +1,42 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/build_config.h" + +#include "drivers/time.h" +#include "drivers/bus_spi.h" +#include "drivers/io.h" +#include "drivers/io_impl.h" + +void initialisePreBootHardware(void) +{ + // User1 + IOInit(DEFIO_IO(PB7), OWNER_SYSTEM, RESOURCE_OUTPUT, 0); + IOConfigGPIO(DEFIO_IO(PB7), IOCFG_OUT_PP); + IOLo(DEFIO_IO(PB7)); + + // User2 + IOInit(DEFIO_IO(PB15), OWNER_SYSTEM, RESOURCE_OUTPUT, 0); + IOConfigGPIO(DEFIO_IO(PB15), IOCFG_OUT_PP); + IOLo(DEFIO_IO(PB15)); +} diff --git a/src/main/target/KAKUTEF4WING/target.c b/src/main/target/KAKUTEF4WING/target.c new file mode 100755 index 00000000000..8f717ed5fd2 --- /dev/null +++ b/src/main/target/KAKUTEF4WING/target.c @@ -0,0 +1,42 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT - DMA1_ST5 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA1_ST0 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA2_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA2_ST7 + + DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP - DMA1_ST4 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEF4WING/target.h b/src/main/target/KAKUTEF4WING/target.h new file mode 100644 index 00000000000..27e600e5d45 --- /dev/null +++ b/src/main/target/KAKUTEF4WING/target.h @@ -0,0 +1,184 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "F4WI" +#define USBD_PRODUCT_STRING "KakuteF4Wing" + +#define USE_TARGET_CONFIG + +// ******* Status LED***************** +#define LED0 PC5 + +// ******* Internal IMU ICM42688****** +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 +#define ICM42605_EXTI_PIN PB12 + +// *************** I2C **************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +// ********** External MAG On I2C1****** +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +// ********** External Devices On I2C1****** +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// ********** Internal BARO On I2C2********* +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +// *************** AT7456 OSD *************** +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PC15 + +// *************** SPI FLASH BLACKBOX********* +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PC14 +#define M25P16_SPI_BUS BUS_SPI3 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** USB VCP ******************** +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_PIN PA8 +#define VBUS_SENSING_ENABLED + +// *************** UART ******************** +#define USE_UART_INVERTER +//UART1 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +//UART2 +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +//The 5V pads close to UART3 a are powered by both BEC and USB +//We config UART3 to serialRX, So Receiver is powered when USB Plug-IN. +//UART3: SerialRX by Default +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 +#define INVERTER_PIN_UART3_RX PC13 + +//UART5 +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +//UART6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +// # define USE_SOFTSERIAL1 +# define SERIAL_PORT_COUNT 6 + +// *************** SPI ******************** +#define USE_SPI +// SPI1: Connected to ICM gyro +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +// SPI2: Connected to OSD +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PC15 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +// SPI3: Connected to flash memory +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PC14 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// *************** Battery Voltage Sense*********** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_SCALE 250 // Current_Meter 1V=40A +#define VBAT_SCALE_DEFAULT 1100 // VBAT_ADC 1V=11V + +// *************** LED_STRIP ********************** +#define USE_LED_STRIP +#define WS2811_PIN PA1 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream4 +#define WS2811_DMA_CHANNEL DMA_Channel_6 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PB7 // USER1 +#define PINIO2_PIN PB15 // USER2 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_GPS) + +// ***********Set rx type and procotol*************** +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define USE_DSHOT +#define USE_ESC_SENSOR + +#define MAX_PWM_OUTPUT_PORTS 6 + + From c1729b5b95ec03d05944ab329e03804f2b384d6e Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 12:10:20 +0200 Subject: [PATCH 008/212] Implemented basic lulu filtering system --- src/main/CMakeLists.txt | 2 + src/main/common/filter.c | 8 +- src/main/common/filter.h | 8 +- src/main/common/lulu.c | 186 +++++++++++++++++++++++++++ src/main/common/lulu.h | 14 ++ src/main/fc/config.c | 12 +- src/main/fc/settings.yaml | 14 +- src/main/sensors/gyro.c | 5 +- src/main/target/BETAFPVF411/target.h | 2 +- 9 files changed, 231 insertions(+), 20 deletions(-) create mode 100644 src/main/common/lulu.c create mode 100644 src/main/common/lulu.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 5e5efd62ec8..6317ac0f475 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -31,6 +31,8 @@ main_sources(COMMON_SRC common/gps_conversion.h common/log.c common/log.h + common/lulu.c + common/lulu.h common/maths.c common/maths.h common/memory.c diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 86aa54a0364..524ebf98fc4 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -23,10 +23,10 @@ #include "platform.h" #include "common/filter.h" +#include "common/lulu.h" #include "common/maths.h" #include "common/utils.h" #include "common/time.h" - // NULL filter float nullFilterApply(void *filter, float input) { @@ -326,6 +326,8 @@ void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFr pt2FilterInit(&filter->pt2, pt2FilterGain(cutoffFrequency, dT)); } if (filterType == FILTER_PT3) { pt3FilterInit(&filter->pt3, pt3FilterGain(cutoffFrequency, dT)); + } if (filterType == FILTER_LULU) { + pt3FilterInit(&filter->lulu, cutoffFrequency); } else { biquadFilterInitLPF(&filter->biquad, cutoffFrequency, refreshRate); } @@ -341,8 +343,10 @@ void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyF *applyFn = (filterApplyFnPtr) pt2FilterApply; } if (filterType == FILTER_PT3) { *applyFn = (filterApplyFnPtr) pt3FilterApply; + } if (filterType == FILTER_LULU) { + *applyFn = (filterApplyFnPtr) luluFilterApply; } else { *applyFn = (filterApplyFnPtr) biquadFilterApply; } } -} \ No newline at end of file +} diff --git a/src/main/common/filter.h b/src/main/common/filter.h index c6cedc86490..9be86b495ce 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -17,6 +17,8 @@ #pragma once +#include "lulu.h" + typedef struct rateLimitFilter_s { float state; } rateLimitFilter_t; @@ -50,13 +52,15 @@ typedef union { pt1Filter_t pt1; pt2Filter_t pt2; pt3Filter_t pt3; + luluFilter_t lulu; } filter_t; typedef enum { FILTER_PT1 = 0, FILTER_BIQUAD, FILTER_PT2, - FILTER_PT3 + FILTER_PT3, + FILTER_LULU } filterType_e; typedef enum { @@ -134,4 +138,4 @@ void alphaBetaGammaFilterInit(alphaBetaGammaFilter_t *filter, float alpha, float float alphaBetaGammaFilterApply(alphaBetaGammaFilter_t *filter, float input); void initFilter(uint8_t filterType, filter_t *filter, float cutoffFrequency, uint32_t refreshRate); -void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn); \ No newline at end of file +void assignFilterApplyFn(uint8_t filterType, float cutoffFrequency, filterApplyFnPtr *applyFn); diff --git a/src/main/common/lulu.c b/src/main/common/lulu.c new file mode 100644 index 00000000000..7a279a98451 --- /dev/null +++ b/src/main/common/lulu.c @@ -0,0 +1,186 @@ +#include "lulu.h" + +#include +#include +#include +#include + +#include "platform.h" + +#include "common/filter.h" +#include "common/maths.h" +#include "common/utils.h" + +#ifdef __ARM_ACLE +#include +#endif /* __ARM_ACLE */ +#include + +void luluFilterInit(luluFilter_t *filter, int N) +{ + if (N > 15) + { + N = 15; + } + if (N < 1) + { + N = 1; + } + filter->N = N; + filter->windowSize = filter->N * 2 + 1; + filter->windowBufIndex = 0; + + memset(filter->luluInterim, 0, sizeof(float) * (filter->windowSize)); + memset(filter->luluInterimB, 0, sizeof(float) * (filter->windowSize)); +} + +FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, int windowSize) +{ + register float curVal = 0; + register float curValB = 0; + for (int N = 1; N <= filterN; N++) + { + int indexNeg = (index + windowSize - 2 * N) % windowSize; + register int curIndex = (indexNeg + 1) % windowSize; + register float prevVal = series[indexNeg]; + register float prevValB = seriesB[indexNeg]; + register int indexPos = (curIndex + N) % windowSize; + for (int i = windowSize - 2 * N; i < windowSize - N; i++) + { + if (indexPos >= windowSize) + { + indexPos = 0; + } + if (curIndex >= windowSize) + { + curIndex = 0; + } + // curIndex = (2 - 1) % 3 = 1 + curVal = series[curIndex]; + curValB = seriesB[curIndex]; + register float nextVal = series[indexPos]; + register float nextValB = seriesB[indexPos]; + // onbump (s, 1, 1, 3) + // if(onBump(series, curIndex, N, windowSize)) + if (prevVal < curVal && curVal > nextVal) + { + float maxValue = MAX(prevVal, nextVal); + + series[curIndex] = maxValue; + register int k = curIndex; + for (int j = 1; j < N; j++) + { + if (++k >= windowSize) + { + k = 0; + } + series[k] = maxValue; + } + } + + if (prevValB < curValB && curValB > nextValB) + { + float maxValue = MAX(prevValB, nextValB); + + curVal = maxValue; + seriesB[curIndex] = maxValue; + register int k = curIndex; + for (int j = 1; j < N; j++) + { + if (++k >= windowSize) + { + k = 0; + } + seriesB[k] = maxValue; + } + } + prevVal = curVal; + prevValB = curValB; + curIndex++; + indexPos++; + } + + curIndex = (indexNeg + 1) % windowSize; + prevVal = series[indexNeg]; + prevValB = seriesB[indexNeg]; + indexPos = (curIndex + N) % windowSize; + for (int i = windowSize - 2 * N; i < windowSize - N; i++) + { + if (indexPos >= windowSize) + { + indexPos = 0; + } + if (curIndex >= windowSize) + { + curIndex = 0; + } + // curIndex = (2 - 1) % 3 = 1 + curVal = series[curIndex]; + curValB = seriesB[curIndex]; + register float nextVal = series[indexPos]; + register float nextValB = seriesB[indexPos]; + + if (prevVal > curVal && curVal < nextVal) + { + float minValue = MIN(prevVal, nextVal); + + curVal = minValue; + series[curIndex] = minValue; + register int k = curIndex; + for (int j = 1; j < N; j++) + { + if (++k >= windowSize) + { + k = 0; + } + series[k] = minValue; + } + } + + if (prevValB > curValB && curValB < nextValB) + { + float minValue = MIN(prevValB, nextValB); + curValB = minValue; + seriesB[curIndex] = minValue; + register int k = curIndex; + for (int j = 1; j < N; j++) + { + if (++k >= windowSize) + { + k = 0; + } + seriesB[k] = minValue; + } + } + prevVal = curVal; + prevValB = curValB; + curIndex++; + indexPos++; + } + } + return (curVal - curValB) / 2; +} + +FAST_CODE float luluFilterPartialApply(luluFilter_t *filter, float input) +{ + // This is the value N of the LULU filter. + register int filterN = filter->N; + // This is the total window size for the rolling buffer + register int filterWindow = filter->windowSize; + + register int windowIndex = filter->windowBufIndex; + register float inputVal = input; + register int newIndex = (windowIndex + 1) % filterWindow; + filter->windowBufIndex = newIndex; + filter->luluInterim[windowIndex] = inputVal; + filter->luluInterimB[windowIndex] = -inputVal; + return fixRoad(filter->luluInterim, filter->luluInterimB, windowIndex, filterN, filterWindow); +} + +FAST_CODE float luluFilterApply(luluFilter_t *filter, float input) +{ + // This is the UL filter + float resultA = luluFilterPartialApply(filter, input); + // We use the median interpretation of this filter to remove bias in the output + return resultA; +} \ No newline at end of file diff --git a/src/main/common/lulu.h b/src/main/common/lulu.h new file mode 100644 index 00000000000..84f1ad93566 --- /dev/null +++ b/src/main/common/lulu.h @@ -0,0 +1,14 @@ +#pragma once + +// Max N = 15 +typedef struct +{ + int windowSize; + int windowBufIndex; + int N; + float luluInterim[32] __attribute__((aligned(128))); + float luluInterimB[32]; +} luluFilter_t; + +void luluFilterInit(luluFilter_t *filter, int N); +float luluFilterApply(luluFilter_t *filter, float input); diff --git a/src/main/fc/config.c b/src/main/fc/config.c index dc249df059b..8739c0ce630 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -193,13 +193,13 @@ void validateAndFixConfig(void) #ifdef USE_ADAPTIVE_FILTER // gyroConfig()->adaptiveFilterMinHz has to be at least 5 units lower than gyroConfig()->gyro_main_lpf_hz - if (gyroConfig()->adaptiveFilterMinHz + 5 > gyroConfig()->gyro_main_lpf_hz) { - gyroConfigMutable()->adaptiveFilterMinHz = gyroConfig()->gyro_main_lpf_hz - 5; - } +// if (gyroConfig()->adaptiveFilterMinHz + 5 > gyroConfig()->gyro_main_lpf_hz) { +// gyroConfigMutable()->adaptiveFilterMinHz = gyroConfig()->gyro_main_lpf_hz - 5; +// } //gyroConfig()->adaptiveFilterMaxHz has to be at least 5 units higher than gyroConfig()->gyro_main_lpf_hz - if (gyroConfig()->adaptiveFilterMaxHz - 5 < gyroConfig()->gyro_main_lpf_hz) { - gyroConfigMutable()->adaptiveFilterMaxHz = gyroConfig()->gyro_main_lpf_hz + 5; - } +// if (gyroConfig()->adaptiveFilterMaxHz - 5 < gyroConfig()->gyro_main_lpf_hz) { +// gyroConfigMutable()->adaptiveFilterMaxHz = gyroConfig()->gyro_main_lpf_hz + 5; +// } #endif if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index cfe40bb400f..fbbdfbbb29a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -119,7 +119,7 @@ tables: - name: filter_type values: ["PT1", "BIQUAD"] - name: filter_type_full - values: ["PT1", "BIQUAD", "PT2", "PT3"] + values: ["PT1", "BIQUAD", "PT2", "PT3", "LULU"] - name: log_level values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"] - name: iterm_relax @@ -219,13 +219,13 @@ groups: default_value: 1000 max: 9000 - name: gyro_anti_aliasing_lpf_hz - description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz" - default_value: 250 + description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In samples" + default_value: 1 field: gyro_anti_aliasing_lpf_hz max: 1000 - name: gyro_main_lpf_hz - description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)" - default_value: 60 + description: "Software based gyro main lowpass filter. Value is samples" + default_value: 3 field: gyro_main_lpf_hz min: 0 max: 500 @@ -254,7 +254,7 @@ groups: max: 10 - name: dynamic_gyro_notch_enabled description: "Enable/disable dynamic gyro notch also known as Matrix Filter" - default_value: ON + default_value: OFF field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool @@ -293,7 +293,7 @@ groups: default_value: 0 - name: setpoint_kalman_enabled description: "Enable Kalman filter on the gyro data" - default_value: ON + default_value: OFF condition: USE_GYRO_KALMAN field: kalmanEnabled type: bool diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 2b0b7d8c9bd..de0ad438d1c 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -244,9 +244,10 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t { *applyFn = nullFilterApply; if (cutoff > 0) { - *applyFn = (filterApplyFnPtr)pt1FilterApply; + *applyFn = (filterApplyFnPtr)luluFilterApply; for (int axis = 0; axis < 3; axis++) { - pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); +// pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); + luluFilterInit(&state[axis].lulu, cutoff); } } } diff --git a/src/main/target/BETAFPVF411/target.h b/src/main/target/BETAFPVF411/target.h index 1f57281d2f4..50b8bb13c10 100644 --- a/src/main/target/BETAFPVF411/target.h +++ b/src/main/target/BETAFPVF411/target.h @@ -71,7 +71,7 @@ // *************** SPI FLASH ************************** #define USE_FLASHFS #define USE_FLASH_M25P16 -#define M25P16_CS_PIN PB2 +#define M25P16_CS_PIN PA0 #define M25P16_SPI_BUS BUS_SPI2 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT From 8eb6fbaae7776ec815ddd976bcae9675d4912318 Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 12:15:34 +0200 Subject: [PATCH 009/212] Fixed bug --- src/main/common/filter.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 524ebf98fc4..5fd72965d85 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -327,7 +327,7 @@ void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFr } if (filterType == FILTER_PT3) { pt3FilterInit(&filter->pt3, pt3FilterGain(cutoffFrequency, dT)); } if (filterType == FILTER_LULU) { - pt3FilterInit(&filter->lulu, cutoffFrequency); + luluFilterInit(&filter->lulu, cutoffFrequency); } else { biquadFilterInitLPF(&filter->biquad, cutoffFrequency, refreshRate); } From 895ff5b77907f2be8b51e1e0d3ba4931b3bbe11b Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 12:27:12 +0200 Subject: [PATCH 010/212] Undid target change --- src/main/target/BETAFPVF411/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/BETAFPVF411/target.h b/src/main/target/BETAFPVF411/target.h index 50b8bb13c10..1f57281d2f4 100644 --- a/src/main/target/BETAFPVF411/target.h +++ b/src/main/target/BETAFPVF411/target.h @@ -71,7 +71,7 @@ // *************** SPI FLASH ************************** #define USE_FLASHFS #define USE_FLASH_M25P16 -#define M25P16_CS_PIN PA0 +#define M25P16_CS_PIN PB2 #define M25P16_SPI_BUS BUS_SPI2 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT From 96217f39a3d47ec664f3353b230714eedf34f3e4 Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 14:38:11 +0200 Subject: [PATCH 011/212] Made improvements as requested --- src/main/common/lulu.c | 12 ++---------- src/main/fc/config.c | 14 +++++++------- src/main/fc/settings.yaml | 19 ++++++++++++------- src/main/sensors/gyro.c | 22 +++++++++++++++------- src/main/sensors/gyro.h | 5 ++++- 5 files changed, 40 insertions(+), 32 deletions(-) diff --git a/src/main/common/lulu.c b/src/main/common/lulu.c index 7a279a98451..c44d6724ec1 100644 --- a/src/main/common/lulu.c +++ b/src/main/common/lulu.c @@ -18,15 +18,7 @@ void luluFilterInit(luluFilter_t *filter, int N) { - if (N > 15) - { - N = 15; - } - if (N < 1) - { - N = 1; - } - filter->N = N; + filter->N = constrain(N, 1, 15); filter->windowSize = filter->N * 2 + 1; filter->windowBufIndex = 0; @@ -183,4 +175,4 @@ FAST_CODE float luluFilterApply(luluFilter_t *filter, float input) float resultA = luluFilterPartialApply(filter, input); // We use the median interpretation of this filter to remove bias in the output return resultA; -} \ No newline at end of file +} diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 8739c0ce630..fb2a83061d8 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -192,14 +192,14 @@ void validateAndFixConfig(void) { #ifdef USE_ADAPTIVE_FILTER - // gyroConfig()->adaptiveFilterMinHz has to be at least 5 units lower than gyroConfig()->gyro_main_lpf_hz -// if (gyroConfig()->adaptiveFilterMinHz + 5 > gyroConfig()->gyro_main_lpf_hz) { -// gyroConfigMutable()->adaptiveFilterMinHz = gyroConfig()->gyro_main_lpf_hz - 5; -// } +// gyroConfig()->adaptiveFilterMinHz has to be at least 5 units lower than gyroConfig()->gyro_main_lpf_hz + if (gyroConfig()->adaptiveFilterMinHz + 5 > gyroConfig()->gyro_main_lpf_hz) { + gyroConfigMutable()->adaptiveFilterMinHz = gyroConfig()->gyro_main_lpf_hz - 5; + } //gyroConfig()->adaptiveFilterMaxHz has to be at least 5 units higher than gyroConfig()->gyro_main_lpf_hz -// if (gyroConfig()->adaptiveFilterMaxHz - 5 < gyroConfig()->gyro_main_lpf_hz) { -// gyroConfigMutable()->adaptiveFilterMaxHz = gyroConfig()->gyro_main_lpf_hz + 5; -// } + if (gyroConfig()->adaptiveFilterMaxHz - 5 < gyroConfig()->gyro_main_lpf_hz) { + gyroConfigMutable()->adaptiveFilterMaxHz = gyroConfig()->gyro_main_lpf_hz + 5; + } #endif if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index fb773b80eae..14484e58ea7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -192,7 +192,7 @@ tables: values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"] enum: led_pin_pwm_mode_e - name: gyro_filter_mode - values: ["STATIC", "DYNAMIC", "ADAPTIVE"] + values: ["STATIC", "DYNAMIC", "ADAPTIVE", "LULU"] enum: gyroFilterType_e constants: @@ -216,22 +216,27 @@ groups: members: - name: looptime description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." - default_value: 1000 + default_value: 500 max: 9000 - name: gyro_anti_aliasing_lpf_hz - description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In samples" - default_value: 1 + description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz" + default_value: 250 field: gyro_anti_aliasing_lpf_hz max: 1000 - - name: gyro_main_lpf_hz - description: "Software based gyro main lowpass filter. Value is samples" + - name: gyro_lulu_sample_count + description: "Gyro lulu sample count, in number of samples." default_value: 3 + field: gyroLuluSampleCount + max: 15 + - name: gyro_main_lpf_hz + description: "Software based gyro main lowpass filter. Value is Hz" + default_value: 60 field: gyro_main_lpf_hz min: 0 max: 500 - name: gyro_filter_mode description: "Specifies the type of the software LPF of the gyro signals." - default_value: "STATIC" + default_value: "LULU" field: gyroFilterMode table: gyro_filter_mode - name: gyro_dyn_lpf_min_hz diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index de0ad438d1c..7a90215be5c 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -240,14 +240,18 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard return gyroHardware; } -static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t cutoff, uint32_t looptime) +static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t cutoff, uint32_t looptime, filterType_e filterType) { *applyFn = nullFilterApply; if (cutoff > 0) { - *applyFn = (filterApplyFnPtr)luluFilterApply; for (int axis = 0; axis < 3; axis++) { -// pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); - luluFilterInit(&state[axis].lulu, cutoff); + if(filterType == FILTER_LULU) { + luluFilterInit(&state[axis].lulu, cutoff); + *applyFn = (filterApplyFnPtr)luluFilterApply; + } else { + pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); + *applyFn = (filterApplyFnPtr)pt1FilterApply; + } } } } @@ -255,10 +259,14 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t static void gyroInitFilters(void) { //First gyro LPF running at full gyro frequency 8kHz - initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime()); + initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime(), FILTER_PT1); - //Second gyro LPF runnig and PID frequency - this filter is dynamic when gyro_use_dyn_lpf = ON - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime()); + if(gyroConfig()->gyroFilterMode == GYRO_FILTER_MODE_LULU) { + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyroLuluSampleCount, getLooptime(), FILTER_LULU); + } else { + //Second gyro LPF runnig and PID frequency - this filter is dynamic when gyro_use_dyn_lpf = ON + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime(), FILTER_PT1); + } #ifdef USE_ADAPTIVE_FILTER if (gyroConfig()->gyroFilterMode == GYRO_FILTER_MODE_ADAPTIVE) { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 910dac2ea00..4b67081a5ae 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -55,7 +55,8 @@ typedef enum { typedef enum { GYRO_FILTER_MODE_STATIC = 0, GYRO_FILTER_MODE_DYNAMIC = 1, - GYRO_FILTER_MODE_ADAPTIVE = 2 + GYRO_FILTER_MODE_ADAPTIVE = 2, + GYRO_FILTER_MODE_LULU = 3 } gyroFilterMode_e; typedef struct gyro_s { @@ -102,6 +103,8 @@ typedef struct gyroConfig_s { float adaptiveFilterIntegratorThresholdLow; #endif uint8_t gyroFilterMode; + + uint8_t gyroLuluSampleCount; } gyroConfig_t; PG_DECLARE(gyroConfig_t, gyroConfig); From fc4db8a3e0fc322f0efed4103721dcf380facbab Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 17:35:28 +0200 Subject: [PATCH 012/212] Updated CLI settings --- docs/Settings.md | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 296d86931ee..e89e43e8c0d 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -808,7 +808,7 @@ Enable/disable dynamic gyro notch also known as Matrix Filter | Default | Min | Max | | --- | --- | --- | -| ON | OFF | ON | +| OFF | OFF | ON | --- @@ -1698,13 +1698,23 @@ Specifies the type of the software LPF of the gyro signals. | Default | Min | Max | | --- | --- | --- | -| STATIC | | | +| LULU | | | + +--- + +### gyro_lulu_sample_count + +Gyro lulu sample count, in number of samples. + +| Default | Min | Max | +| --- | --- | --- | +| 3 | | 15 | --- ### gyro_main_lpf_hz -Software based gyro main lowpass filter. Value is cutoff frequency (Hz) +Software based gyro main lowpass filter. Value is Hz | Default | Min | Max | | --- | --- | --- | @@ -2198,7 +2208,7 @@ This is the main loop time (in us). Changing this affects PID effect with some P | Default | Min | Max | | --- | --- | --- | -| 1000 | | 9000 | +| 500 | | 9000 | --- @@ -5728,7 +5738,7 @@ Enable Kalman filter on the gyro data | Default | Min | Max | | --- | --- | --- | -| ON | OFF | ON | +| OFF | OFF | ON | --- From 6e5704f5ff33d72096b5cfdb36fe165fb83e5a82 Mon Sep 17 00:00:00 2001 From: Peter Peiser Date: Mon, 17 Jun 2024 17:38:31 +0200 Subject: [PATCH 013/212] Reverted unnecessary changes in setting descriptions --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index e89e43e8c0d..1a2de99f720 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1714,7 +1714,7 @@ Gyro lulu sample count, in number of samples. ### gyro_main_lpf_hz -Software based gyro main lowpass filter. Value is Hz +Software based gyro main lowpass filter. Value is cutoff frequency (Hz) | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 14484e58ea7..289b4eae84a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -229,7 +229,7 @@ groups: field: gyroLuluSampleCount max: 15 - name: gyro_main_lpf_hz - description: "Software based gyro main lowpass filter. Value is Hz" + description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)" default_value: 60 field: gyro_main_lpf_hz min: 0 From da4b30014ab79af711ec26088bcbce03d881bac6 Mon Sep 17 00:00:00 2001 From: jamming Date: Fri, 21 Jun 2024 11:22:45 +0800 Subject: [PATCH 014/212] Fix DMA conflict between SPI,I2C and PWM Channels --- src/main/target/KAKUTEF4WING/hardware_setup.c | 6 +-- src/main/target/KAKUTEF4WING/target.c | 14 +++---- src/main/target/KAKUTEF4WING/target.h | 37 +++++++++---------- 3 files changed, 28 insertions(+), 29 deletions(-) diff --git a/src/main/target/KAKUTEF4WING/hardware_setup.c b/src/main/target/KAKUTEF4WING/hardware_setup.c index f78fd65cd4c..d2045cc0f01 100644 --- a/src/main/target/KAKUTEF4WING/hardware_setup.c +++ b/src/main/target/KAKUTEF4WING/hardware_setup.c @@ -31,9 +31,9 @@ void initialisePreBootHardware(void) { // User1 - IOInit(DEFIO_IO(PB7), OWNER_SYSTEM, RESOURCE_OUTPUT, 0); - IOConfigGPIO(DEFIO_IO(PB7), IOCFG_OUT_PP); - IOLo(DEFIO_IO(PB7)); + IOInit(DEFIO_IO(PB14), OWNER_SYSTEM, RESOURCE_OUTPUT, 0); + IOConfigGPIO(DEFIO_IO(PB14), IOCFG_OUT_PP); + IOLo(DEFIO_IO(PB14)); // User2 IOInit(DEFIO_IO(PB15), OWNER_SYSTEM, RESOURCE_OUTPUT, 0); diff --git a/src/main/target/KAKUTEF4WING/target.c b/src/main/target/KAKUTEF4WING/target.c index 8f717ed5fd2..8c2240a9c3b 100755 --- a/src/main/target/KAKUTEF4WING/target.c +++ b/src/main/target/KAKUTEF4WING/target.c @@ -29,14 +29,14 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT - DMA1_ST5 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA1_ST0 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA2_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA2_ST7 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1_OUT - DMA2_ST1_CH6 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA2_ST6_CH0 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT - DMA1_ST7_CH5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST2_CH5 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA2_ST2_CH0 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA2_ST7_CH7 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP - DMA1_ST4 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP-DMA1_ST6_CH3 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEF4WING/target.h b/src/main/target/KAKUTEF4WING/target.h index 27e600e5d45..cb29473d06a 100644 --- a/src/main/target/KAKUTEF4WING/target.h +++ b/src/main/target/KAKUTEF4WING/target.h @@ -40,24 +40,21 @@ #define ICM42605_EXTI_PIN PB12 // *************** I2C **************** -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 +#define USE_I2C #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 #define I2C2_SDA PB11 -// ********** External MAG On I2C1****** +// ********** External MAG On I2C2****** #define USE_MAG -#define MAG_I2C_BUS BUS_I2C1 +#define MAG_I2C_BUS BUS_I2C2 #define USE_MAG_ALL -// ********** External Devices On I2C1****** -#define TEMPERATURE_I2C_BUS BUS_I2C1 -#define PITOT_I2C_BUS BUS_I2C1 +// ********** External Devices On I2C2****** +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define PITOT_I2C_BUS BUS_I2C2 #define USE_RANGEFINDER -#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C2 // ********** Internal BARO On I2C2********* #define USE_BARO @@ -81,23 +78,23 @@ // *************** USB VCP ******************** #define USB_IO #define USE_VCP -#define VBUS_SENSING_PIN PA8 +#define VBUS_SENSING_PIN PA10 #define VBUS_SENSING_ENABLED // *************** UART ******************** #define USE_UART_INVERTER //UART1 #define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 //UART2 #define USE_UART2 #define UART2_RX_PIN PA3 #define UART2_TX_PIN PA2 -//The 5V pads close to UART3 a are powered by both BEC and USB -//We config UART3 to serialRX, So Receiver is powered when USB Plug-IN. +//The 4V5 pads close to UART3 are powered by both BEC and USB +//Config UART3 to serialRX, So Receiver is powered when USB Plug-IN. //UART3: SerialRX by Default #define USE_UART3 #define UART3_RX_PIN PC11 @@ -142,6 +139,8 @@ // *************** Battery Voltage Sense*********** #define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream4 #define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_2_PIN PC1 #define VBAT_ADC_CHANNEL ADC_CHN_1 @@ -152,14 +151,14 @@ // *************** LED_STRIP ********************** #define USE_LED_STRIP #define WS2811_PIN PA1 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST4_HANDLER -#define WS2811_DMA_STREAM DMA1_Stream4 -#define WS2811_DMA_CHANNEL DMA_Channel_6 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST6_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream6 +#define WS2811_DMA_CHANNEL DMA_Channel_3 // *************** PINIO *************************** #define USE_PINIO #define USE_PINIOBOX -#define PINIO1_PIN PB7 // USER1 +#define PINIO1_PIN PB14 // USER1 #define PINIO2_PIN PB15 // USER2 #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_GPS) From e0d141a1ef691cc6dd6c8299f2ec1acd08083349 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 21 Jun 2024 19:23:58 +0200 Subject: [PATCH 015/212] Set digital channels --- src/main/io/servo_sbus.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/io/servo_sbus.c b/src/main/io/servo_sbus.c index ba0edcc5327..bfcd71b1158 100644 --- a/src/main/io/servo_sbus.c +++ b/src/main/io/servo_sbus.c @@ -109,6 +109,8 @@ void sbusServoUpdate(uint8_t index, uint16_t value) case 13: sbusFrame.channels.chan13 = sbusEncodeChannelValue(value); break; case 14: sbusFrame.channels.chan14 = sbusEncodeChannelValue(value); break; case 15: sbusFrame.channels.chan15 = sbusEncodeChannelValue(value); break; + case 16: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_17) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_17) ; break; + case 17: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_18) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_18) ; break; default: break; } From 1a0b6e18615c8db104222ea05b5a3e4e5a80212c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 21 Jun 2024 19:27:32 +0200 Subject: [PATCH 016/212] Bump max servos to 18 --- src/main/drivers/pwm_mapping.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index cfb96afadbf..08123130f2c 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -24,13 +24,12 @@ #if defined(TARGET_MOTOR_COUNT) #define MAX_MOTORS TARGET_MOTOR_COUNT -#define MAX_SERVOS 16 - #else #define MAX_MOTORS 12 -#define MAX_SERVOS 16 #endif +#define MAX_SERVOS 18 + #define PWM_TIMER_HZ 1000000 #define PULSE_1MS (1000) // 1ms pulse width From b6f29761270b261290d549bcf02a64ff43d33d61 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 21 Jun 2024 19:31:46 +0200 Subject: [PATCH 017/212] Expand servo count to 18 --- src/main/flight/servos.h | 2 +- src/main/rx/sbus_channels.c | 2 -- src/main/rx/sbus_channels.h | 2 ++ 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index d271142ece0..1ae7d536a65 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -20,7 +20,7 @@ #include "config/parameter_group.h" #include "programming/logic_condition.h" -#define MAX_SUPPORTED_SERVOS 16 +#define MAX_SUPPORTED_SERVOS 18 // These must be consecutive typedef enum { diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index 380b1b32240..99ca76393d6 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -28,8 +28,6 @@ #include "rx/sbus_channels.h" -#define SBUS_FLAG_CHANNEL_17 (1 << 0) -#define SBUS_FLAG_CHANNEL_18 (1 << 1) #define SBUS_DIGITAL_CHANNEL_MIN 173 #define SBUS_DIGITAL_CHANNEL_MAX 1812 diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index 5e8a6a02681..467fdda5afc 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -22,6 +22,8 @@ #define SBUS_MAX_CHANNEL 18 +#define SBUS_FLAG_CHANNEL_17 (1 << 0) +#define SBUS_FLAG_CHANNEL_18 (1 << 1) #define SBUS_FLAG_SIGNAL_LOSS (1 << 2) #define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3) From 47bc883c7e19f5b214919588fe1c14b84047c9aa Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 21 Jun 2024 20:00:49 +0200 Subject: [PATCH 018/212] Expand inputs and mixer to full 24 channels --- src/main/fc/rc_controls.h | 34 ++++++++++++++++++++++------------ src/main/flight/servos.c | 10 ++++++++++ src/main/flight/servos.h | 10 ++++++++++ 3 files changed, 42 insertions(+), 12 deletions(-) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 8d5ee66bd73..3705a29c3a1 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -26,18 +26,28 @@ typedef enum rc_alias { PITCH, YAW, THROTTLE, - AUX1, - AUX2, - AUX3, - AUX4, - AUX5, - AUX6, - AUX7, - AUX8, - AUX9, - AUX10, - AUX11, - AUX12 + AUX1, // 5 + AUX2, // 6 + AUX3, // 7 + AUX4, // 8 + AUX5, // 9 + AUX6, // 10 + AUX7, // 11 + AUX8, // 12 + AUX9, // 13 + AUX10, // 14 + AUX11, // 15 + AUX12, // 16 + AUX13, // 17 + AUX14, // 18 +#ifdef USE_24CHANNELS + AUX15, // 19 + AUX16, // 20 + AUX17, // 21 + AUX18, // 22 + AUX19, // 23 + AUX20, // 24 +#endif } rc_alias_e; typedef enum { diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index e77e0788904..5ac98f78215 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -347,6 +347,16 @@ void servoMixer(float dT) input[INPUT_RC_CH14] = GET_RX_CHANNEL_INPUT(AUX10); input[INPUT_RC_CH15] = GET_RX_CHANNEL_INPUT(AUX11); input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12); + input[INPUT_RC_CH17] = GET_RX_CHANNEL_INPUT(AUX13); + input[INPUT_RC_CH18] = GET_RX_CHANNEL_INPUT(AUX14); +#ifdef USE_24CHANNELS + input[INPUT_RC_CH19] = GET_RX_CHANNEL_INPUT(AUX15); + input[INPUT_RC_CH20] = GET_RX_CHANNEL_INPUT(AUX16); + input[INPUT_RC_CH21] = GET_RX_CHANNEL_INPUT(AUX17); + input[INPUT_RC_CH22] = GET_RX_CHANNEL_INPUT(AUX18); + input[INPUT_RC_CH23] = GET_RX_CHANNEL_INPUT(AUX19); + input[INPUT_RC_CH24] = GET_RX_CHANNEL_INPUT(AUX20); +#endif #undef GET_RX_CHANNEL_INPUT #ifdef USE_HEADTRACKER diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 1ae7d536a65..4f6e5777967 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -66,6 +66,16 @@ typedef enum { INPUT_HEADTRACKER_PAN = 39, INPUT_HEADTRACKER_TILT = 40, INPUT_HEADTRACKER_ROLL = 41, + INPUT_RC_CH17 = 42, + INPUT_RC_CH18 = 43, +#ifdef USE_24CHANNELS + INPUT_RC_CH19 = 44, + INPUT_RC_CH20 = 45, + INPUT_RC_CH21 = 46, + INPUT_RC_CH22 = 47, + INPUT_RC_CH23 = 48, + INPUT_RC_CH24 = 49, +#endif INPUT_SOURCE_COUNT } inputSource_e; From 646bb78064db2f7ff3a329c9a4c6c36e9c4c9ae8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 22 Jun 2024 12:17:13 +0200 Subject: [PATCH 019/212] Basics. Needs filling in values and sending out frames --- src/main/CMakeLists.txt | 2 + src/main/telemetry/sbus2.c | 27 ++++++++++ src/main/telemetry/sbus2.h | 104 +++++++++++++++++++++++++++++++++++++ 3 files changed, 133 insertions(+) create mode 100644 src/main/telemetry/sbus2.c create mode 100644 src/main/telemetry/sbus2.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 2e2b6cb2b20..8644101e930 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -610,6 +610,8 @@ main_sources(COMMON_SRC telemetry/mavlink.h telemetry/msp_shared.c telemetry/msp_shared.h + telemetry/sbus2.c + telemetry/sbus2.h telemetry/smartport.c telemetry/smartport.h telemetry/sim.c diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c new file mode 100644 index 00000000000..f192160f8a2 --- /dev/null +++ b/src/main/telemetry/sbus2.c @@ -0,0 +1,27 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include "sbus2.h" + +const uint8_t Slot_ID[SBUS2_SLOT_COUNT] = { + 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, + 0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3, + 0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB, + 0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB +}; + + diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h new file mode 100644 index 00000000000..c5b13e12fc7 --- /dev/null +++ b/src/main/telemetry/sbus2.h @@ -0,0 +1,104 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#include + +#define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 + +#define SBUS2_SLOT_COUNT 32 + +// Information on SBUS2 sensors from: https://github.com/BrushlessPower/SBUS2-Telemetry/tree/master + +extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; + + +// Temperature: +// Max 125C +// value | 0x4000 +typedef struct sbus2_telemetry_temp_payload_s { + uint8_t tempHigh; // temp | 0x4000; // 125c + uint8_t tempLow; +} sbsu2_telemetry_temp_payload_t; + + +// Temperature: +// Max 200C +// temp | 0x8000 +typedef struct sbus2_telemetry_temp200_payload_s { + uint8_t tempLow; // temp | 0x8000; // 200c + uint8_t tempHigh; +} sbsu2_telemetry_temp200_payload_t; + +// RPM: +// (RPM / 6) max: 0xFFFF +typedef struct sbus2_telemetry_rpm_payload_s { + uint8_t rpmHigh; // RPM / 6, capped at 0xFFFF + uint8_t rpmLow; +} sbsu2_telemetry_rpm_payload_t; + +// Voltage: 1 or 2 slots +// 0x8000 = rx voltage? +// max input: 0x1FFF +typedef struct sbus2_telemetry_voltage_payload_s { + uint8_t voltageHigh; // 2 slots // Voltage 1: value | 0x8000 + uint8_t voltageLow; // max input value: 0x1FFF +} sbsu2_telemetry_voltage_payload_t; + +// Current +// 3 frames +// 1: current +// Max input: 0x3FFF +// input |= 0x4000 +// input &= 0x7FFF +// 2: voltage +// same as voltage frame. may not need ot be capped. +// 3: Capacity +typedef struct sbus2_telemetry_current_payload_s { + uint8_t currentHigh; + uint8_t currentLow; +} sbsu2_telemetry_current_payload_t; + +typedef struct sbus2_telemetry_capacity_payload_s { + uint8_t capacityHigh; + uint8_t capacityLow; +} sbsu2_telemetry_capacity_payload_t; + + +// GPS +// frames: +// 1: Speed +// 2: Altitude +// 3: Vario +// 4,5: LAT +// 5,6: LON + + +typedef struct sbus2_telemetry_frame_s { + uint8_t slotId; + union { + uint8_t data[2]; + sbsu2_telemetry_temp_payload_t temp125; + sbsu2_telemetry_temp200_payload_t temp200; + sbsu2_telemetry_rpm_payload_t rpm; + sbsu2_telemetry_voltage_payload_t voltage; + sbsu2_telemetry_current_payload_t current; + sbsu2_telemetry_capacity_payload_t capacity; + } payload; +} sbus2_telemetry_frame_t; From 8d74e702b6f69a55d218b1f37e9be9f9c3c440f8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 22 Jun 2024 06:53:31 -0400 Subject: [PATCH 020/212] Update CMakeLists.txt tabs vs spaces --- src/main/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 8644101e930..9a0b09090af 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -610,8 +610,8 @@ main_sources(COMMON_SRC telemetry/mavlink.h telemetry/msp_shared.c telemetry/msp_shared.h - telemetry/sbus2.c - telemetry/sbus2.h + telemetry/sbus2.c + telemetry/sbus2.h telemetry/smartport.c telemetry/smartport.h telemetry/sim.c From 9f9b867e9de449df7c2b3566826dc5e65d944c21 Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Sun, 23 Jun 2024 17:16:04 +0800 Subject: [PATCH 021/212] Update accgyro_bmi088.c: get BMI088 acc aligned --- src/main/drivers/accgyro/accgyro_bmi088.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/accgyro/accgyro_bmi088.c b/src/main/drivers/accgyro/accgyro_bmi088.c index 8988685c835..7f219f212bd 100644 --- a/src/main/drivers/accgyro/accgyro_bmi088.c +++ b/src/main/drivers/accgyro/accgyro_bmi088.c @@ -214,6 +214,7 @@ bool bmi088AccDetect(accDev_t *acc) acc->initFn = bmi088AccInit; acc->readFn = bmi088AccRead; + acc->accAlign = acc->busDev->param; return true; } From b3425abb5f9d80dc093e999c19618f2f53b8e869 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 24 Jun 2024 11:15:17 +0200 Subject: [PATCH 022/212] Revert to previous defaults --- src/main/fc/settings.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 289b4eae84a..f1d729ae35c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -259,7 +259,7 @@ groups: max: 10 - name: dynamic_gyro_notch_enabled description: "Enable/disable dynamic gyro notch also known as Matrix Filter" - default_value: OFF + default_value: ON field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool @@ -298,7 +298,7 @@ groups: default_value: 0 - name: setpoint_kalman_enabled description: "Enable Kalman filter on the gyro data" - default_value: OFF + default_value: ON condition: USE_GYRO_KALMAN field: kalmanEnabled type: bool From 1e5d2b93d07f810e93fb9cb934498c4658d5ff4b Mon Sep 17 00:00:00 2001 From: jamming Date: Mon, 24 Jun 2024 17:15:29 +0800 Subject: [PATCH 023/212] Add ICM-42688P to KakuteF4 --- src/main/target/KAKUTEF4/target.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index bc921c9f3f8..c1ce47b9e80 100644 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -57,6 +57,11 @@ #define MPU6000_CS_PIN PC4 #define MPU6000_SPI_BUS BUS_SPI1 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN PC4 +#define ICM42605_SPI_BUS BUS_SPI1 + #if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) || defined(KAKUTEF4V24) # define USE_I2C # define USE_I2C_DEVICE_1 From 116c9e274f4c52ca705db0ea9b964c8af8356d0d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 24 Jun 2024 11:23:37 +0200 Subject: [PATCH 024/212] Fix defaults initialization --- src/main/fc/settings.yaml | 2 +- src/main/sensors/gyro.c | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index f1d729ae35c..7c9a416e38b 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -236,7 +236,7 @@ groups: max: 500 - name: gyro_filter_mode description: "Specifies the type of the software LPF of the gyro signals." - default_value: "LULU" + default_value: "STATIC" field: gyroFilterMode table: gyro_filter_mode - name: gyro_dyn_lpf_min_hz diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 7a90215be5c..b4723f0da74 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -96,7 +96,7 @@ EXTENDED_FASTRAM secondaryDynamicGyroNotchState_t secondaryDynamicGyroNotchState #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 10); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 11); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT, @@ -132,6 +132,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .adaptiveFilterIntegratorThresholdLow = SETTING_GYRO_ADAPTIVE_FILTER_INTEGRATOR_THRESHOLD_LOW_DEFAULT, #endif .gyroFilterMode = SETTING_GYRO_FILTER_MODE_DEFAULT, + .gyroLuluSampleCount = SETTING_GYRO_LULU_SAMPLE_COUNT_DEFAULT ); STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware) From df29310c3a62a7cbeeaf81b2892e3b4874153f30 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 12:54:27 +0200 Subject: [PATCH 025/212] USE_MAG_ALL --- src/main/target/ATOMRCF405V2/target.h | 7 +------ src/main/target/FLYWOOF405S_AIO/target.h | 8 +------- src/main/target/GEPRCF745_BT_HD/target.h | 7 +------ src/main/target/JHEMCUF405/target.h | 8 +------- src/main/target/JHEMCUF722/target.h | 7 +------ src/main/target/SDMODELH7V1/target.h | 8 +------- src/main/target/TAKERF722SE/target.h | 5 +---- src/main/target/ZEEZF7/target.h | 4 ---- 8 files changed, 7 insertions(+), 47 deletions(-) diff --git a/src/main/target/ATOMRCF405V2/target.h b/src/main/target/ATOMRCF405V2/target.h index b8315653899..232ac47d953 100644 --- a/src/main/target/ATOMRCF405V2/target.h +++ b/src/main/target/ATOMRCF405V2/target.h @@ -81,12 +81,7 @@ */ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#defiine USE_MAG_ALL /* * Barometer diff --git a/src/main/target/FLYWOOF405S_AIO/target.h b/src/main/target/FLYWOOF405S_AIO/target.h index c25dedfeb9b..4250943633e 100644 --- a/src/main/target/FLYWOOF405S_AIO/target.h +++ b/src/main/target/FLYWOOF405S_AIO/target.h @@ -68,13 +68,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define USE_RANGEFINDER_HCSR04_I2C diff --git a/src/main/target/GEPRCF745_BT_HD/target.h b/src/main/target/GEPRCF745_BT_HD/target.h index 3d61f663dd8..c6c84a32ad3 100644 --- a/src/main/target/GEPRCF745_BT_HD/target.h +++ b/src/main/target/GEPRCF745_BT_HD/target.h @@ -89,12 +89,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/JHEMCUF405/target.h b/src/main/target/JHEMCUF405/target.h index 6a5b2f52ab4..3cd6fd1e3ea 100644 --- a/src/main/target/JHEMCUF405/target.h +++ b/src/main/target/JHEMCUF405/target.h @@ -68,13 +68,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define USE_RANGEFINDER_HCSR04_I2C diff --git a/src/main/target/JHEMCUF722/target.h b/src/main/target/JHEMCUF722/target.h index 9d34e5c8201..2777df365e3 100644 --- a/src/main/target/JHEMCUF722/target.h +++ b/src/main/target/JHEMCUF722/target.h @@ -107,12 +107,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // Onboard Flash #define USE_SPI_DEVICE_3 diff --git a/src/main/target/SDMODELH7V1/target.h b/src/main/target/SDMODELH7V1/target.h index cc4d39cf6c8..1d3f90b8f9d 100644 --- a/src/main/target/SDMODELH7V1/target.h +++ b/src/main/target/SDMODELH7V1/target.h @@ -93,13 +93,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/TAKERF722SE/target.h b/src/main/target/TAKERF722SE/target.h index 817dc535f03..599d5610ad4 100644 --- a/src/main/target/TAKERF722SE/target.h +++ b/src/main/target/TAKERF722SE/target.h @@ -121,11 +121,8 @@ #define USE_BARO_MS5611 #define USE_MAG +#define USE_MAG_ALL #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index 28395b274fb..563a5814891 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -107,10 +107,6 @@ #define USE_BARO #define USE_BARO_DPS310 -#define USE_MAG -#define USE_MAG_QMC5883 -#endif - #if defined ZEEZF7V2 || defined ZEEZF7V3 #define USE_I2C #define USE_BARO From b07caf31906cb3cf6b8d9611d69ca5107c01cfac Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 12:57:44 +0200 Subject: [PATCH 026/212] fix typo --- src/main/target/ATOMRCF405V2/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/ATOMRCF405V2/target.h b/src/main/target/ATOMRCF405V2/target.h index 232ac47d953..32c064f4f21 100644 --- a/src/main/target/ATOMRCF405V2/target.h +++ b/src/main/target/ATOMRCF405V2/target.h @@ -81,7 +81,7 @@ */ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#defiine USE_MAG_ALL +#define USE_MAG_ALL /* * Barometer From ea658710f8b07956057d9a86474cb17e6afd8007 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 13:01:00 +0200 Subject: [PATCH 027/212] Another fix --- src/main/target/ZEEZF7/target.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index 563a5814891..2ab83104d3a 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -107,6 +107,11 @@ #define USE_BARO #define USE_BARO_DPS310 +#define USE_MAG +#define USE_MAG_ALL + +#endif + #if defined ZEEZF7V2 || defined ZEEZF7V3 #define USE_I2C #define USE_BARO From b1b787d40a133659e261fae2218b5c6928dba7e9 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 24 Jun 2024 17:33:25 +0200 Subject: [PATCH 028/212] docs update --- docs/Settings.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 5b762084ab8..4cdf101c587 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -808,7 +808,7 @@ Enable/disable dynamic gyro notch also known as Matrix Filter | Default | Min | Max | | --- | --- | --- | -| OFF | OFF | ON | +| ON | OFF | ON | --- @@ -1778,7 +1778,7 @@ Specifies the type of the software LPF of the gyro signals. | Default | Min | Max | | --- | --- | --- | -| LULU | | | +| STATIC | | | --- @@ -5868,7 +5868,7 @@ Enable Kalman filter on the gyro data | Default | Min | Max | | --- | --- | --- | -| OFF | OFF | ON | +| ON | OFF | ON | --- From bd7f488e952129c4079b3a421c1e350ddf5970f4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 23:18:20 +0200 Subject: [PATCH 029/212] More plumbing. Add SBUS2 option to rx type. Add method to query active telemetry frame --- src/main/fc/settings.yaml | 2 +- src/main/rx/rx.c | 1 + src/main/rx/rx.h | 1 + src/main/rx/sbus.h | 4 ++++ src/main/target/common.h | 5 +++++ src/main/telemetry/sbus2.c | 13 +++++++++++++ src/main/telemetry/sbus2.h | 39 ++++++++++++++++++++++---------------- 7 files changed, 48 insertions(+), 17 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a27e9599db7..865d7fc90a1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -23,7 +23,7 @@ tables: values: ["NONE", "SERIAL", "MSP", "SIM (SITL)"] enum: rxReceiverType_e - name: serial_rx - values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK", "FBUS"] + values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK", "FBUS", "SBUS2"] - name: blackbox_device values: ["SERIAL", "SPIFLASH", "SDCARD"] - name: motor_pwm_protocol diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 881b1128c47..f941eaebe20 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -196,6 +196,7 @@ bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig break; #endif #ifdef USE_SERIALRX_SBUS + case SERIALRX_SBUS2: case SERIALRX_SBUS: enabled = sbusInit(rxConfig, rxRuntimeConfig); break; diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 1aee04ec083..9e4816ec64c 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -81,6 +81,7 @@ typedef enum { SERIALRX_GHST, SERIALRX_MAVLINK, SERIALRX_FBUS, + SERIALRX_SBUS2, } rxSerialReceiverType_e; #ifdef USE_24CHANNELS diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index 1fcd3680d0e..07f4b900e1d 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -21,3 +21,7 @@ bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); + +#ifdef USE_SBUS2_TELEMETRY +uint8_t sbusGetCurrentTelemetryFrame(); +#endif diff --git a/src/main/target/common.h b/src/main/target/common.h index 8bb735fc437..3238abea018 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -195,6 +195,11 @@ #define USE_HEADTRACKER_SERIAL #define USE_HEADTRACKER_MSP +#ifndef STM32F4 +// needs bi-direction inverter, no available on F4 hardware. +#define USE_SBUS2_TELEMETRY +#endif + //Designed to free space of F722 and F411 MCUs #if (MCU_FLASH_SIZE > 512) #define USE_VTX_FFPV diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index f192160f8a2..206d7fdd732 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -15,8 +15,16 @@ * along with INAV. If not, see . */ +#include + +#include "platform.h" + +#include "build/debug.h" + #include "sbus2.h" +#ifdef USE_SBUS2_TELEMETRY + const uint8_t Slot_ID[SBUS2_SLOT_COUNT] = { 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, 0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3, @@ -25,3 +33,8 @@ const uint8_t Slot_ID[SBUS2_SLOT_COUNT] = { }; +sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; +uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; + + +#endif \ No newline at end of file diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index c5b13e12fc7..8fad140c895 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -20,23 +20,25 @@ #include -#define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 - -#define SBUS2_SLOT_COUNT 32 +#include "platform.h" -// Information on SBUS2 sensors from: https://github.com/BrushlessPower/SBUS2-Telemetry/tree/master +#define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 -extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; +#define SBUS2_SLOT_COUNT 32 +#define SBUS2_TELEMETRY_ITEM_SIZE 3 +#define SBUS2_TELEMETRY_SLOTS 8 +#define SBUS2_TELEMETRY_PAGES 4 +#ifdef USE_SBUS2_TELEMETRY +// Information on SBUS2 sensors from: https://github.com/BrushlessPower/SBUS2-Telemetry/tree/master // Temperature: // Max 125C // value | 0x4000 typedef struct sbus2_telemetry_temp_payload_s { uint8_t tempHigh; // temp | 0x4000; // 125c uint8_t tempLow; -} sbsu2_telemetry_temp_payload_t; - +} __attribute__((packed)) sbsu2_telemetry_temp_payload_t; // Temperature: // Max 200C @@ -44,14 +46,14 @@ typedef struct sbus2_telemetry_temp_payload_s { typedef struct sbus2_telemetry_temp200_payload_s { uint8_t tempLow; // temp | 0x8000; // 200c uint8_t tempHigh; -} sbsu2_telemetry_temp200_payload_t; +} __attribute__((packed)) sbsu2_telemetry_temp200_payload_t; // RPM: // (RPM / 6) max: 0xFFFF typedef struct sbus2_telemetry_rpm_payload_s { uint8_t rpmHigh; // RPM / 6, capped at 0xFFFF uint8_t rpmLow; -} sbsu2_telemetry_rpm_payload_t; +} __attribute__((packed)) sbsu2_telemetry_rpm_payload_t; // Voltage: 1 or 2 slots // 0x8000 = rx voltage? @@ -59,7 +61,7 @@ typedef struct sbus2_telemetry_rpm_payload_s { typedef struct sbus2_telemetry_voltage_payload_s { uint8_t voltageHigh; // 2 slots // Voltage 1: value | 0x8000 uint8_t voltageLow; // max input value: 0x1FFF -} sbsu2_telemetry_voltage_payload_t; +} __attribute__((packed)) sbsu2_telemetry_voltage_payload_t; // Current // 3 frames @@ -73,13 +75,12 @@ typedef struct sbus2_telemetry_voltage_payload_s { typedef struct sbus2_telemetry_current_payload_s { uint8_t currentHigh; uint8_t currentLow; -} sbsu2_telemetry_current_payload_t; +} __attribute__((packed)) sbsu2_telemetry_current_payload_t; typedef struct sbus2_telemetry_capacity_payload_s { uint8_t capacityHigh; uint8_t capacityLow; -} sbsu2_telemetry_capacity_payload_t; - +} __attribute__((packed)) sbsu2_telemetry_capacity_payload_t; // GPS // frames: @@ -89,10 +90,10 @@ typedef struct sbus2_telemetry_capacity_payload_s { // 4,5: LAT // 5,6: LON - typedef struct sbus2_telemetry_frame_s { uint8_t slotId; - union { + union + { uint8_t data[2]; sbsu2_telemetry_temp_payload_t temp125; sbsu2_telemetry_temp200_payload_t temp200; @@ -101,4 +102,10 @@ typedef struct sbus2_telemetry_frame_s { sbsu2_telemetry_current_payload_t current; sbsu2_telemetry_capacity_payload_t capacity; } payload; -} sbus2_telemetry_frame_t; +} __attribute__((packed)) sbus2_telemetry_frame_t; + +extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; +extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; +extern uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; + +#endif \ No newline at end of file From 4c56952e15848d3c6811e0751d69d9934967d91d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 23:46:16 +0200 Subject: [PATCH 030/212] Setup serial port for bi direction, half duplex operation --- src/main/rx/sbus.c | 29 +++++++++++++++++++++++++++-- src/main/rx/sbus.h | 3 ++- src/main/telemetry/sbus2.h | 4 ++-- 3 files changed, 31 insertions(+), 5 deletions(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 98570387654..8984be2abbe 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -66,6 +66,9 @@ typedef struct sbusFrameData_s { timeUs_t lastActivityTimeUs; } sbusFrameData_t; +static uint8_t sbus2ActiveTelemetryFrame = 0; +timeUs_t frameTime = 0; + // Receive ISR callback static void sbusDataReceive(uint16_t c, void *data) { @@ -99,9 +102,19 @@ static void sbusDataReceive(uint16_t c, void *data) switch (frame->endByte) { case 0x00: // This is S.BUS 1 case 0x04: // S.BUS 2 receiver voltage + sbus2ActiveTelemetryFrame = 0; + goto process_end_frame; case 0x14: // S.BUS 2 GPS/baro + sbus2ActiveTelemetryFrame = 1; + goto process_end_frame; case 0x24: // Unknown SBUS2 data + sbus2ActiveTelemetryFrame = 2; + goto process_end_frame; case 0x34: // Unknown SBUS2 data + sbus2ActiveTelemetryFrame = 3; + process_end_frame: + frameTime = currentTimeUs; + frameValid = true; sbusFrameData->state = STATE_SBUS_WAIT_SYNC; break; @@ -179,9 +192,10 @@ static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeC sbusDataReceive, &sbusFrameData, sbusBaudRate, - portShared ? MODE_RXTX : MODE_RX, + (portShared || rxConfig->serialrx_provider == SERIALRX_SBUS2) ? MODE_RXTX : MODE_RX, SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | + ((rxConfig->serialrx_provider == SERIALRX_SBUS2) ? SERIAL_BIDIR : 0) | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); @@ -203,4 +217,15 @@ bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig { return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST); } -#endif + +#if defined(USE_TELEMETRY) && defined(USE_SBUS2_TELEMETRY) +uint8_t sbusGetLastFrameTime(void) { + return frameTime; +} + +uint8_t sbusGetCurrentTelemetryFrame(void) { + return sbus2ActiveTelemetryFrame; +} +#endif // USE_TELEMETRY && USE_SBUS2_TELEMETRY + +#endif // USE_SERIAL_RX diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index 07f4b900e1d..f698eecb8eb 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -23,5 +23,6 @@ bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeCon bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); #ifdef USE_SBUS2_TELEMETRY -uint8_t sbusGetCurrentTelemetryFrame(); +uint8_t sbusGetCurrentTelemetryFrame(void); +uint8_t sbusGetLastFrameTime(void); #endif diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 8fad140c895..a40bc1f3983 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -24,12 +24,12 @@ #define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 -#define SBUS2_SLOT_COUNT 32 #define SBUS2_TELEMETRY_ITEM_SIZE 3 #define SBUS2_TELEMETRY_SLOTS 8 #define SBUS2_TELEMETRY_PAGES 4 +#define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) -#ifdef USE_SBUS2_TELEMETRY +#if defined(USE_TELEMETRY) && defined(USE_SBUS2_TELEMETRY) // Information on SBUS2 sensors from: https://github.com/BrushlessPower/SBUS2-Telemetry/tree/master // Temperature: From 459fec940f520d71edfb62436b138e3500cbc0a5 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 24 Jun 2024 23:58:13 +0200 Subject: [PATCH 031/212] Update frame check --- src/main/rx/sbus.c | 31 +++++++++++++++---------------- src/main/rx/sbus.h | 2 +- 2 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 8984be2abbe..8a5c3f926a1 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -66,7 +66,7 @@ typedef struct sbusFrameData_s { timeUs_t lastActivityTimeUs; } sbusFrameData_t; -static uint8_t sbus2ActiveTelemetryFrame = 0; +static uint8_t sbus2ActiveTelemetryPage = 0; timeUs_t frameTime = 0; // Receive ISR callback @@ -101,19 +101,18 @@ static void sbusDataReceive(uint16_t c, void *data) // Do some sanity check switch (frame->endByte) { case 0x00: // This is S.BUS 1 - case 0x04: // S.BUS 2 receiver voltage - sbus2ActiveTelemetryFrame = 0; - goto process_end_frame; - case 0x14: // S.BUS 2 GPS/baro - sbus2ActiveTelemetryFrame = 1; - goto process_end_frame; - case 0x24: // Unknown SBUS2 data - sbus2ActiveTelemetryFrame = 2; - goto process_end_frame; - case 0x34: // Unknown SBUS2 data - sbus2ActiveTelemetryFrame = 3; - process_end_frame: - frameTime = currentTimeUs; + case 0x04: // S.BUS 2 telemetry page 1 + case 0x14: // S.BUS 2 telemetry page 2 + case 0x24: // S.BUS 2 telemetry page 3 + case 0x34: // S.BUS 2 telemetry page 4 + if(frame->endByte & 0x4) { + sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF; + frameTime = currentTimeUs; + } else { + sbus2ActiveTelemetryPage = 0; + frameTime = -1; + } + frameValid = true; sbusFrameData->state = STATE_SBUS_WAIT_SYNC; @@ -223,8 +222,8 @@ uint8_t sbusGetLastFrameTime(void) { return frameTime; } -uint8_t sbusGetCurrentTelemetryFrame(void) { - return sbus2ActiveTelemetryFrame; +uint8_t sbusGetCurrentTelemetryPage(void) { + return sbus2ActiveTelemetryPage; } #endif // USE_TELEMETRY && USE_SBUS2_TELEMETRY diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index f698eecb8eb..94af636a43f 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -23,6 +23,6 @@ bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeCon bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); #ifdef USE_SBUS2_TELEMETRY -uint8_t sbusGetCurrentTelemetryFrame(void); +uint8_t sbusGetCurrentTelemetryPage(void); uint8_t sbusGetLastFrameTime(void); #endif From a3a129e6ee1c34b022cc7f70366a85b7306a9821 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 00:52:55 +0200 Subject: [PATCH 032/212] Plugin some of the telemetry functions. Basic squeleton in place. Need to update telemetry data and avoid sending telemetry slot twice. --- src/main/rx/sbus.h | 2 ++ src/main/telemetry/sbus2.c | 36 ++++++++++++++++++++++++++++------ src/main/telemetry/sbus2.h | 1 + src/main/telemetry/telemetry.c | 4 ++++ 4 files changed, 37 insertions(+), 6 deletions(-) diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index 94af636a43f..b3356ace83e 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -19,6 +19,8 @@ #define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case +#include "rx/rx.h" + bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 206d7fdd732..309ca045016 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -21,20 +21,44 @@ #include "build/debug.h" -#include "sbus2.h" +#include "common/time.h" + +#include "telemetry/sbus2.h" + +#include "rx/sbus.h" #ifdef USE_SBUS2_TELEMETRY -const uint8_t Slot_ID[SBUS2_SLOT_COUNT] = { - 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, - 0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3, - 0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB, - 0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB +const uint8_t sbus2SlotIds[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = { + {0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3}, + {0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3}, + {0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB}, + {0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB} }; sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; +void handleSbus2Telemetry(timeUs_t currentTimeUs) +{ + uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); + uint8_t lastFrame = sbusGetLastFrameTime(); + + timeUs_t elapsedTime = currentTimeUs - lastFrame - MS2US(2); + + // 2ms after sbus2 frame = slot 0 + // +660us for next slot + if(elapsedTime > 0) { + uint8_t slot = elapsedTime % 660; + if(slot < SBUS2_TELEMETRY_SLOTS) { + if(sbusTelemetryDataStatus[telemetryPage][slot] != 0) { + sbusTelemetryData[telemetryPage][slot].slotId = sbus2SlotIds[telemetryPage][slot]; + // send + sbusTelemetryDataStatus[telemetryPage][slot] = 0; + } + } + } +} #endif \ No newline at end of file diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index a40bc1f3983..dce16c48441 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -108,4 +108,5 @@ extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; extern uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; +void handleSbus2Telemetry(timeUs_t currentTimeUs); #endif \ No newline at end of file diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index d6c8e355d86..dd6e08961e0 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -245,6 +245,10 @@ void telemetryProcess(timeUs_t currentTimeUs) #ifdef USE_TELEMETRY_GHST handleGhstTelemetry(currentTimeUs); #endif + +#ifdef USE_TELMETRY_SBUS2 + handleSbus2Telemetry(currentTimeUs); +#endif } #endif From 596c025ef1a629aa8738ae2faaa55b9b5362062b Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 25 Jun 2024 14:36:59 +0200 Subject: [PATCH 033/212] Remove of register optimization in favor or relying on GCC optimization. --- src/main/common/lulu.c | 41 +++++++++++++++++++++-------------------- 1 file changed, 21 insertions(+), 20 deletions(-) diff --git a/src/main/common/lulu.c b/src/main/common/lulu.c index c44d6724ec1..8ab7803ed1b 100644 --- a/src/main/common/lulu.c +++ b/src/main/common/lulu.c @@ -28,16 +28,17 @@ void luluFilterInit(luluFilter_t *filter, int N) FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, int windowSize) { - register float curVal = 0; - register float curValB = 0; + float curVal = 0; + float curValB = 0; for (int N = 1; N <= filterN; N++) { int indexNeg = (index + windowSize - 2 * N) % windowSize; - register int curIndex = (indexNeg + 1) % windowSize; - register float prevVal = series[indexNeg]; - register float prevValB = seriesB[indexNeg]; - register int indexPos = (curIndex + N) % windowSize; - for (int i = windowSize - 2 * N; i < windowSize - N; i++) + int curIndex = (indexNeg + 1) % windowSize; + float prevVal = series[indexNeg]; + float prevValB = seriesB[indexNeg]; + int indexPos = (curIndex + N) % windowSize; + + for (int i = windowSize - 2 * N; i < windowSize - N; i++) { if (indexPos >= windowSize) { @@ -50,8 +51,8 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i // curIndex = (2 - 1) % 3 = 1 curVal = series[curIndex]; curValB = seriesB[curIndex]; - register float nextVal = series[indexPos]; - register float nextValB = seriesB[indexPos]; + float nextVal = series[indexPos]; + float nextValB = seriesB[indexPos]; // onbump (s, 1, 1, 3) // if(onBump(series, curIndex, N, windowSize)) if (prevVal < curVal && curVal > nextVal) @@ -59,7 +60,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i float maxValue = MAX(prevVal, nextVal); series[curIndex] = maxValue; - register int k = curIndex; + int k = curIndex; for (int j = 1; j < N; j++) { if (++k >= windowSize) @@ -76,7 +77,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i curVal = maxValue; seriesB[curIndex] = maxValue; - register int k = curIndex; + int k = curIndex; for (int j = 1; j < N; j++) { if (++k >= windowSize) @@ -109,8 +110,8 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i // curIndex = (2 - 1) % 3 = 1 curVal = series[curIndex]; curValB = seriesB[curIndex]; - register float nextVal = series[indexPos]; - register float nextValB = seriesB[indexPos]; + float nextVal = series[indexPos]; + float nextValB = seriesB[indexPos]; if (prevVal > curVal && curVal < nextVal) { @@ -118,7 +119,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i curVal = minValue; series[curIndex] = minValue; - register int k = curIndex; + int k = curIndex; for (int j = 1; j < N; j++) { if (++k >= windowSize) @@ -134,7 +135,7 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i float minValue = MIN(prevValB, nextValB); curValB = minValue; seriesB[curIndex] = minValue; - register int k = curIndex; + int k = curIndex; for (int j = 1; j < N; j++) { if (++k >= windowSize) @@ -156,13 +157,13 @@ FAST_CODE float fixRoad(float *series, float *seriesB, int index, int filterN, i FAST_CODE float luluFilterPartialApply(luluFilter_t *filter, float input) { // This is the value N of the LULU filter. - register int filterN = filter->N; + int filterN = filter->N; // This is the total window size for the rolling buffer - register int filterWindow = filter->windowSize; + int filterWindow = filter->windowSize; - register int windowIndex = filter->windowBufIndex; - register float inputVal = input; - register int newIndex = (windowIndex + 1) % filterWindow; + int windowIndex = filter->windowBufIndex; + float inputVal = input; + int newIndex = (windowIndex + 1) % filterWindow; filter->windowBufIndex = newIndex; filter->luluInterim[windowIndex] = inputVal; filter->luluInterimB[windowIndex] = -inputVal; From 1a274336a6e29d7b840a9cea9897aeaa530f546e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 14:43:53 +0200 Subject: [PATCH 034/212] Add task to send telemtery info --- src/main/fc/fc_tasks.c | 13 +++++++++++++ src/main/scheduler/scheduler.h | 4 ++++ src/main/telemetry/sbus2.c | 10 ++++++++-- src/main/telemetry/sbus2.h | 6 +++++- 4 files changed, 30 insertions(+), 3 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 6918b9a6dab..5728b9752cd 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -437,6 +437,10 @@ void fcTasksInit(void) setTaskEnabled(TASK_HEADTRACKER, true); #endif +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) + setTaskEnabled(TASK_TELEMETRY_SBUS2, rxConfig->serialrx_provider == SERIALRX_SBUS2); +#endif + #ifdef USE_ADAPTIVE_FILTER setTaskEnabled(TASK_ADAPTIVE_FILTER, ( gyroConfig()->gyroFilterMode == GYRO_FILTER_MODE_ADAPTIVE && @@ -726,4 +730,13 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) + [TASK_TELEMETRY_SBUS2] = { + .taskName = "SBUS2_TELEMETRY", + .taskFunc = taskSendSbus2Telemetry, + .desiredPeriod = TASK_PERIOD_US(300), + .staticPriority = TASK_PRIORITY_IDLE, + }, +#endif + }; diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index a43206840fe..176812d8f3f 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -133,6 +133,10 @@ typedef enum { TASK_HEADTRACKER, #endif +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) + TASK_TELEMETRY_SBUS2, +#endif + /* Count of real tasks */ TASK_COUNT, diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 309ca045016..fdd6295718e 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -41,10 +41,16 @@ sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; void handleSbus2Telemetry(timeUs_t currentTimeUs) +{ + UNUSED(currentTimeUs); + + // update telemetry info +} + +void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); uint8_t lastFrame = sbusGetLastFrameTime(); - timeUs_t elapsedTime = currentTimeUs - lastFrame - MS2US(2); // 2ms after sbus2 frame = slot 0 @@ -61,4 +67,4 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) } } -#endif \ No newline at end of file +#endif diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index dce16c48441..7e59782a1d1 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -108,5 +108,9 @@ extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; extern uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; +// refresh telemetry buffers void handleSbus2Telemetry(timeUs_t currentTimeUs); -#endif \ No newline at end of file + +// time critical, send sbus2 data +void taskSendSbus2Telemetry(timeUs_t currentTimeUs); +#endif From 6da4f35a354e4034584914f50080acb917157668 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 15:00:05 +0200 Subject: [PATCH 035/212] fix sitl --- src/main/telemetry/sbus2.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index fdd6295718e..ed258ee15f4 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -21,6 +21,7 @@ #include "build/debug.h" +#include "common/utils.h" #include "common/time.h" #include "telemetry/sbus2.h" From ce5156ba18cc1a12f1830a91cf0d8073be3929af Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 23:08:05 +0200 Subject: [PATCH 036/212] Use correct method to set message rate for newer ublox devices. As a bonus: Add gpssats and showdebug cli commmands. --- src/main/build/debug.h | 3 +- src/main/common/printf.c | 1 + src/main/fc/cli.c | 161 +++++++++++++++++++++++++++++++++++++- src/main/fc/settings.yaml | 3 +- src/main/io/gps_ublox.c | 77 +++++++++++++----- src/main/io/gps_ublox.h | 44 ++++++++++- 6 files changed, 263 insertions(+), 26 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index fea424b9005..7ee74471544 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -76,7 +76,8 @@ typedef enum { DEBUG_POS_EST, DEBUG_ADAPTIVE_FILTER, DEBUG_HEADTRACKING, - DEBUG_COUNT + DEBUG_GPS, + DEBUG_COUNT // also update debugModeNames in cli.c } debugType_e; #ifdef SITL_BUILD diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 5e72f726b04..39dc01ed4b5 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -162,6 +162,7 @@ int tfp_nformat(void *putp, int size, void (*putf) (void *, char), const char *f written += putchw(putp, end, putf, w, lz, bf); break; } + case 'i': case 'd':{ #ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 0d54cab4398..83d3ac51e64 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -187,9 +187,39 @@ static const char * const blackboxIncludeFlagNames[] = { }; #endif -/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */ +static const char *debugModeNames[DEBUG_COUNT] = { + "NONE", + "AGL", + "FLOW_RAW", + "FLOW", + "ALWAYS", + "SAG_COMP_VOLTAGE", + "VIBE", + "CRUISE", + "REM_FLIGHT_TIME", + "SMARTAUDIO", + "ACC", + "NAV_YAW", + "PCF8574", + "DYN_GYRO_LPF", + "AUTOLEVEL", + "ALTITUDE", + "AUTOTRIM", + "AUTOTUNE", + "RATE_DYNAMICS", + "LANDING", + "POS_EST", + "ADAPTIVE_FILTER", + "HEADTRACKER", + "GPS" +}; + +/* Sensor names (used in lookup tables for *_hardware settings and in status + command output) */ // sync with gyroSensor_e -static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270","LSM6DXX", "FAKE"}; +static const char *const gyroNames[] = { + "NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", + "ICM20689", "BMI088", "ICM42605", "BMI270", "LSM6DXX", "FAKE"}; // sync this with sensors_e static const char * const sensorTypeNames[] = { @@ -253,6 +283,7 @@ static void cliPrintLine(const char *str) cliPrintLinefeed(); } + static void cliPrintError(const char *str) { cliPrint("### ERROR: "); @@ -4259,6 +4290,130 @@ typedef struct { } #endif +static void cliCmdDebug(char *arg) +{ + UNUSED(arg); + if (debugMode != DEBUG_NONE) { + cliPrintLinef("Debug fields: [%s (%i)]", debugMode < DEBUG_COUNT ? debugModeNames[debugMode] : "unknown", debugMode); + for (int i = 0; i < DEBUG32_VALUE_COUNT; i++) { + cliPrintLinef("debug[%d] = %d", i, debug[i]); + } + } else { + cliPrintLine("Debug mode is disabled"); + } +} + + +#if defined(USE_GPS) && defined(USE_GPS_PROTO_UBLOX) + +static const char* _ubloxGetSigId(uint8_t gnssId, uint8_t sigId) +{ + if(gnssId == 0) { + switch(sigId) { + case 0: return "GPS L1C/A"; + case 3: return "GPS L2 CL"; + case 4: return "GPS L2 CM"; + case 6: return "GPS L5 I"; + case 7: return "GPS L5 Q"; + default: return "GPS Unknown"; + } + } else if(gnssId == 1) { + switch(sigId) { + case 0: return "SBAS L1C/A"; + default: return "SBAS Unknown"; + } + } else if(gnssId == 2) { + switch(sigId) { + case 0: return "Galileo E1 C"; + case 1: return "Galileo E1 B"; + case 3: return "Galileo E5 al"; + case 4: return "Galileo E5 aQ"; + case 5: return "Galileo E5 bl"; + case 6: return "Galileo E5 bQ"; + default: return "Galileo Unknown"; + } + } else if(gnssId == 3) { + switch(sigId) { + case 0: return "BeiDou B1I D1"; + case 1: return "BeiDou B1I D2"; + case 2: return "BeiDou B2I D1"; + case 3: return "BeiDou B2I D2"; + case 5: return "BeiDou B1C"; + case 7: return "BeiDou B2a"; + default: return "BeiDou Unknown"; + } + } else if(gnssId == 5) { + switch(sigId) { + case 0: return "QZSS L1C/A"; + case 1: return "QZSS L1S"; + case 4: return "QZSS L2 CM"; + case 5: return "QZSS L2 CL"; + case 8: return "QZSS L5 I"; + case 9: return "QZSS L5 Q"; + default: return "QZSS Unknown"; + } + } else if(gnssId == 6) { + switch(sigId) { + case 0: return "GLONASS L1 OF"; + case 2: return "GLONASS L2 OF"; + default: return "GLONASS Unknown"; + } + } + + return "Unknown GNSS/SigId"; +} + +static const char *_ubloxGetQuality(uint8_t quality) +{ + switch(quality) { + case 0: return "No signal"; + case 1: return "Searching signal..."; + case 2: return "Signal acquired"; + case 3: return "Signal detected but unusable"; + case 4: return "Code locked and time synch"; + case 5: + case 6: + case 7: + return "Code and carrier locked and time synch"; + default: return "Unknown"; + } +} + +static void cliUbloxPrintSatelites(char *arg) +{ + UNUSED(arg); + if(!isGpsUblox()) { + cliPrint("GPS is not UBLOX"); + return; + } + + cliPrintLine("UBLOX Satelites"); + + for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) + { + const ubx_nav_sig_info *sat = gpsGetUbloxSatelite(i); + if(sat == NULL || sat->svId == 0) { + continue; + } + + cliPrintLinef("satelite: %d:%d", sat->gnssId, sat->svId); + cliPrintLinef("sigId: %d (%s)", sat->sigId, _ubloxGetSigId(sat->gnssId, sat->sigId)); + cliPrintLinef("signal strength: %i dbHz", sat->cno); + cliPrintLinef("quality: %i (%s)", sat->quality, _ubloxGetQuality(sat->quality)); + //cliPrintLinef("Correlation: %i", sat->corrSource); + //cliPrintLinef("Iono model: %i", sat->ionoModel); + cliPrintLinef("signal flags: 0x%02X", sat->sigFlags); + if(sat->sigFlags & 0x01) { + cliPrintLine("signal: Healthy"); + } else if (sat->sigFlags & 0x02) { + cliPrintLine("signal: Unhealthy"); + } else { + cliPrintLine("signal: Unknown"); + } + } +} +#endif + static void cliHelp(char *cmdline); // should be sorted a..z for bsearch() @@ -4318,6 +4473,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet), #ifdef USE_GPS CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough), + CLI_COMMAND_DEF("gpssats", "show GPS satellites", NULL, cliUbloxPrintSatelites), #endif CLI_COMMAND_DEF("help", NULL, NULL, cliHelp), #ifdef USE_LED_STRIP @@ -4370,6 +4526,7 @@ const clicmd_t cmdTable[] = { #ifdef USE_SDCARD CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo), #endif + CLI_COMMAND_DEF("showdebug", "Show debug fields.", NULL, cliCmdDebug), CLI_COMMAND_DEF("status", "show status", NULL, cliStatus), CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks), #ifdef USE_TEMPERATURE_SENSOR diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a27e9599db7..d8dd7d6fbee 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -83,7 +83,8 @@ tables: values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE", - "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", "ADAPTIVE_FILTER", "HEADTRACKER" ] + "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", + "ADAPTIVE_FILTER", "HEADTRACKER", "GPS" ] - name: aux_operator values: ["OR", "AND"] enum: modeActivationOperator_e diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 52b6329d9f2..b6ea20e854f 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -43,6 +43,7 @@ #include "fc/config.h" #include "fc/runtime_config.h" #include "fc/settings.h" +#include "fc/cli.h" #include "io/serial.h" #include "io/gps.h" @@ -84,6 +85,8 @@ static const char * baudInitDataNMEA[GPS_BAUDRATE_COUNT] = { "$PUBX,41,1,0003,0001,921600,0*15\r\n" // GPS_BAUDRATE_921600 }; +static ubx_nav_sig_info satelites[UBLOX_MAX_SIGNALS] = {}; + // Packet checksum accumulators static uint8_t _ck_a; static uint8_t _ck_b; @@ -145,6 +148,7 @@ static union { ubx_nav_timeutc timeutc; ubx_ack_ack ack; ubx_mon_gnss gnss; + ubx_nav_sig navsig; uint8_t bytes[UBLOX_BUFFER_SIZE]; } _buffer; @@ -551,6 +555,7 @@ static uint32_t gpsDecodeHardwareVersion(const char * szBuf, unsigned nBufSize) static bool gpsParseFrameUBLOX(void) { + DEBUG_SET(DEBUG_GPS, 7, 42); switch (_msg_id) { case MSG_POSLLH: gpsSolDRV.llh.lon = _buffer.posllh.longitude; @@ -601,6 +606,10 @@ static bool gpsParseFrameUBLOX(void) } break; case MSG_PVT: + { + static int pvtCount = 0; + DEBUG_SET(DEBUG_GPS, 1, pvtCount++); + } next_fix_type = gpsMapFixType(_buffer.pvt.fix_status & NAV_STATUS_FIX_VALID, _buffer.pvt.fix_type); gpsSolDRV.fixType = next_fix_type; gpsSolDRV.llh.lon = _buffer.pvt.longitude; @@ -684,6 +693,30 @@ static bool gpsParseFrameUBLOX(void) } } break; + case MSG_NAV_SAT: + if (_class == CLASS_NAV) { + static int satInfoCount = 0; + DEBUG_SET(DEBUG_GPS, 2, satInfoCount++); + gpsSolDRV.numSat = _buffer.svinfo.numCh; + } + break; + case MSG_SIG_INFO: + if (_class == CLASS_NAV && _buffer.navsig.version == 0) { + if(_buffer.navsig.numSigs < UBLOX_MAX_SIGNALS) + { + for(int i=0; i < UBLOX_MAX_SIGNALS && i < _buffer.navsig.numSigs; ++i) + { + memcpy(&satelites[i], &_buffer.navsig.sig[i], sizeof(ubx_nav_sig_info)); + } + for(int i = _buffer.navsig.numSigs; i < UBLOX_MAX_SIGNALS; ++i) + { + satelites[i].svId = 0; // no used + } + } + static int sigInfoCount = 0; + DEBUG_SET(DEBUG_GPS, 0, sigInfoCount++); + } + break; case MSG_ACK_ACK: if ((_ack_state == UBX_ACK_WAITING) && (_buffer.ack.msg == _ack_waiting_msg)) { _ack_state = UBX_ACK_GOT_ACK; @@ -856,27 +889,20 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence - if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9) { - configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9 || gpsState.swVersionMajor > 23 || (gpsState.swVersionMajor == 23 && gpsState.swVersionMinor >=1)) { // > 23.01, don't use configureMSG + ubx_config_data8_payload_t rateValues[] = { + {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, + {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, + }; - configureMSG(MSG_CLASS_UBX, MSG_NAV_SIG, 0); + ubloxSendSetCfgBytes(rateValues, 7); ptWait(_ack_state == UBX_ACK_GOT_ACK); + //ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz @@ -1134,11 +1160,22 @@ void gpsHandleUBLOX(void) bool isGpsUblox(void) { - if(gpsState.gpsConfig->provider == GPS_UBLOX || gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) { + if(gpsState.gpsPort != NULL && (gpsState.gpsConfig->provider == GPS_UBLOX || gpsState.gpsConfig->provider == GPS_UBLOX7PLUS)) { return true; } return false; } + +const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index) +{ + if(index < UBLOX_MAX_SIGNALS) { + return &satelites[index]; + } + + return NULL; +} + + #endif diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 87cffa9c50b..041f98653b5 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -28,7 +28,8 @@ extern "C" { #define GPS_CFG_CMD_TIMEOUT_MS 500 #define GPS_VERSION_RETRY_TIMES 3 -#define MAX_UBLOX_PAYLOAD_SIZE 256 +#define UBLOX_MAX_SIGNALS 32 +#define MAX_UBLOX_PAYLOAD_SIZE 640 // enough for anyone? // UBX-NAV-SIG info would be UBLOX_MAX_SIGNALS + 8 for (32 * 16) + 8 = 520 bytes #define UBLOX_BUFFER_SIZE MAX_UBLOX_PAYLOAD_SIZE #define UBLOX_SBAS_MESSAGE_LENGTH 16 #define GPS_CAPA_INTERVAL 5000 @@ -55,6 +56,13 @@ extern "C" { #define UBX_HW_VERSION_UBLOX9 900 #define UBX_HW_VERSION_UBLOX10 1000 +#define UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1 0x2091002a // U1 +#define UBLOX_CFG_MSGOUT_NAV_SAT_UART1 0x20910016 // U1 +#define UBLOX_CFG_MSGOUT_NAV_SIG_UART1 0x20910346 // U1 +#define UBLOX_CFG_MSGOUT_NAV_STATUS_UART1 0x2091001b // U1 +#define UBLOX_CFG_MSGOUT_NAV_VELNED_UART1 0x20910043 // U1 +#define UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1 0x2091005c // U1 +#define UBLOX_CFG_MSGOUT_NAV_PVT_UART1 0x20910007 // U1 #define UBLOX_CFG_SIGNAL_SBAS_ENA 0x10310020 // U1 #define UBLOX_CFG_SIGNAL_SBAS_L1CA_ENA 0x10310005 // U1 @@ -169,6 +177,34 @@ typedef struct { uint8_t reserved; } __attribute__((packed)) ubx_config_data_header_v1_t; +typedef struct { + uint8_t gnssId; // gnssid 0 = GPS, 1 = SBAS, 2 = GALILEO, 3 = BEIDOU, 4 = IMES, 5 = QZSS, 6 = GLONASS + uint8_t svId; // space vehicle ID + uint8_t sigId; // new style signal ID (gnssId:sigId) + uint8_t freqId; // 0-13 slot +, 0-13, glonass only + int16_t prRes; // pseudo range residual (0.1m) + uint8_t cno; // carrier to noise density ratio (dbHz) + uint8_t quality; // 0 = no signal, 1 = search, 2 = acq, 3 = detected, 4 = code lock + time, 5,6,7 = code/carrier lock + time + uint8_t corrSource; // Correction source: 0 = no correction, 1 = SBAS, 2 = BeiDou, 3 = RTCM2, 4 = RTCM3 OSR, 5 = RTCM3 SSR, 6 = QZSS SLAS, 7 = SPARTN + uint8_t ionoModel; // 0 = no mode, 1 = Klobuchar GPS, 2 = SBAS, 3 = Klobuchar BeiDou, 8 = Iono derived from dual frequency observations + uint16_t sigFlags; // bit:0-1, 0 = unknown, 1 = healthy, 2 = unhealthy + // bit2: pseudorange smoothed, + // bit3: pseudorange used, + // bit4: carrioer range used; + // bit5: doppler used + // bit6: pseudorange corrections used + // bit7: carrier correction used + // bit8: doper corrections used + uint8_t reserved; +} __attribute__((packed)) ubx_nav_sig_info; + +typedef struct { + uint32_t time; // GPS iToW + uint8_t version; // We support version 0 + uint8_t numSigs; // number of signals + uint16_t reserved; + ubx_nav_sig_info sig[UBLOX_MAX_SIGNALS]; // 32 signals +} __attribute__((packed)) ubx_nav_sig; #define MAX_GNSS 7 #define MAX_GNSS_SIZE_BYTES (sizeof(ubx_gnss_msg_t) + sizeof(ubx_gnss_element_t)*MAX_GNSS) @@ -350,6 +386,8 @@ typedef struct { uint8_t reserverd3; } ubx_mon_gnss; + + typedef struct { uint8_t msg_class; uint8_t msg; @@ -394,7 +432,8 @@ typedef enum { MSG_CFG_NAV_SETTINGS = 0x24, MSG_CFG_SBAS = 0x16, MSG_CFG_GNSS = 0x3e, - MSG_MON_GNSS = 0x28 + MSG_MON_GNSS = 0x28, + MSG_SIG_INFO = 0x43 } ubx_protocol_bytes_t; typedef enum { @@ -428,6 +467,7 @@ bool gpsUbloxSendCommand(uint8_t *rawCommand, uint16_t commandLen, uint16_t time bool isGpsUblox(void); +const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index); #ifdef __cplusplus } From eca4674af44edd2a2237d8d233d77973afde82c7 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 23:24:10 +0200 Subject: [PATCH 037/212] Add some extra gps status info to status command --- src/main/fc/cli.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 83d3ac51e64..be7858fadda 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3889,10 +3889,14 @@ static void cliStatus(char *cmdline) cliPrintLinefeed(); #endif - if (featureConfigured(FEATURE_GPS) && (gpsConfig()->provider == GPS_UBLOX || gpsConfig()->provider == GPS_UBLOX7PLUS)) { + if (featureConfigured(FEATURE_GPS) && isGpsUblox()) { cliPrint("GPS: "); cliPrintf("HW Version: %s Proto: %d.%02d Baud: %d", getGpsHwVersion(), getGpsProtoMajorVersion(), getGpsProtoMinorVersion(), getGpsBaudrate()); cliPrintLinefeed(); + cliPrintLinef("SATS: %i", gpsSol.numSat); + cliPrintLinef("HDOP: %f", (double)(gpsSol.hdop / (float)HDOP_SCALE)); + cliPrintLinef("EPH: %f m", (double)(gpsSol.eph / 100.0f)); + cliPrintLinef("EPV: %f m", (double)(gpsSol.epv / 100.0f)); //cliPrintLinef(" GNSS Capabilities: %d", gpsUbloxCapLastUpdate()); cliPrintLinef(" GNSS Capabilities:"); cliPrintLine(" GNSS Provider active/default"); From 5451413cc3d6671a1a87522af2dd40d8ecceff00 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 25 Jun 2024 23:25:06 +0200 Subject: [PATCH 038/212] Status formatting --- src/main/fc/cli.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index be7858fadda..8df40e20066 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3893,10 +3893,10 @@ static void cliStatus(char *cmdline) cliPrint("GPS: "); cliPrintf("HW Version: %s Proto: %d.%02d Baud: %d", getGpsHwVersion(), getGpsProtoMajorVersion(), getGpsProtoMinorVersion(), getGpsBaudrate()); cliPrintLinefeed(); - cliPrintLinef("SATS: %i", gpsSol.numSat); - cliPrintLinef("HDOP: %f", (double)(gpsSol.hdop / (float)HDOP_SCALE)); - cliPrintLinef("EPH: %f m", (double)(gpsSol.eph / 100.0f)); - cliPrintLinef("EPV: %f m", (double)(gpsSol.epv / 100.0f)); + cliPrintLinef(" SATS: %i", gpsSol.numSat); + cliPrintLinef(" HDOP: %f", (double)(gpsSol.hdop / (float)HDOP_SCALE)); + cliPrintLinef(" EPH : %f m", (double)(gpsSol.eph / 100.0f)); + cliPrintLinef(" EPV : %f m", (double)(gpsSol.epv / 100.0f)); //cliPrintLinef(" GNSS Capabilities: %d", gpsUbloxCapLastUpdate()); cliPrintLinef(" GNSS Capabilities:"); cliPrintLine(" GNSS Provider active/default"); From 615402a9f672831b32846d36759d69fba2992a25 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 00:45:12 +0200 Subject: [PATCH 039/212] Add line feed to sparete satelites --- src/main/fc/cli.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 8df40e20066..872d9cbc933 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4414,6 +4414,7 @@ static void cliUbloxPrintSatelites(char *arg) } else { cliPrintLine("signal: Unknown"); } + cliPrintLinefeed(); } } #endif From 19a4fc3cdc97f2d74b4e653b5d64c0fc3801674d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 01:08:31 +0200 Subject: [PATCH 040/212] Cleanup --- src/main/io/gps_ublox.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index b6ea20e854f..a22858ef8fc 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -555,7 +555,6 @@ static uint32_t gpsDecodeHardwareVersion(const char * szBuf, unsigned nBufSize) static bool gpsParseFrameUBLOX(void) { - DEBUG_SET(DEBUG_GPS, 7, 42); switch (_msg_id) { case MSG_POSLLH: gpsSolDRV.llh.lon = _buffer.posllh.longitude; @@ -702,6 +701,8 @@ static bool gpsParseFrameUBLOX(void) break; case MSG_SIG_INFO: if (_class == CLASS_NAV && _buffer.navsig.version == 0) { + static int sigInfoCount = 0; + DEBUG_SET(DEBUG_GPS, 0, sigInfoCount++); if(_buffer.navsig.numSigs < UBLOX_MAX_SIGNALS) { for(int i=0; i < UBLOX_MAX_SIGNALS && i < _buffer.navsig.numSigs; ++i) @@ -713,8 +714,6 @@ static bool gpsParseFrameUBLOX(void) satelites[i].svId = 0; // no used } } - static int sigInfoCount = 0; - DEBUG_SET(DEBUG_GPS, 0, sigInfoCount++); } break; case MSG_ACK_ACK: @@ -902,7 +901,6 @@ STATIC_PROTOTHREAD(gpsConfigure) ubloxSendSetCfgBytes(rateValues, 7); ptWait(_ack_state == UBX_ACK_GOT_ACK); - //ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz From bab841c83dcf9a6445ac385cfa14007d2e934f6f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 11:46:36 +0200 Subject: [PATCH 041/212] UBLOX8 did not support new message and used old configuratoin interface. Provide alternative way of setting message rates in case firmware is too old. Try to enable NAV_SIG but fallback to NAV_SAT. TODO: fill nav sat info into satelites Current status of GPS debug counters 0: NAV_SIG count 1: MSG_PVT count 2: MSG_SAT count 3: 4: 5: flags.pvt 6: flags.sat 7: flags.sig --- src/main/fc/cli.c | 4 +- src/main/io/gps_private.h | 6 +++ src/main/io/gps_ublox.c | 84 +++++++++++++++++++++++++++++++++------ 3 files changed, 79 insertions(+), 15 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 872d9cbc933..fa8ec75b615 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4386,8 +4386,8 @@ static const char *_ubloxGetQuality(uint8_t quality) static void cliUbloxPrintSatelites(char *arg) { UNUSED(arg); - if(!isGpsUblox()) { - cliPrint("GPS is not UBLOX"); + if(!isGpsUblox() /*|| !(gpsState.flags.sig || gpsState.flags.sat)*/) { + cliPrint("GPS is not UBLOX or does not report satelites."); return; } diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index ee2a0b1e215..e5234e70248 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -50,6 +50,12 @@ typedef struct { gpsBaudRate_e baudrateIndex; gpsBaudRate_e autoBaudrateIndex; // Driver internal use (for autoBaud) uint8_t autoConfigStep; // Driver internal use (for autoConfig) + struct + { + uint8_t pvt : 1; + uint8_t sig : 1; + uint8_t sat : 1; + } flags; timeMs_t lastStateSwitchMs; timeMs_t lastLastMessageMs; diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index a22858ef8fc..35b0de92ae6 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -696,7 +696,10 @@ static bool gpsParseFrameUBLOX(void) if (_class == CLASS_NAV) { static int satInfoCount = 0; DEBUG_SET(DEBUG_GPS, 2, satInfoCount++); - gpsSolDRV.numSat = _buffer.svinfo.numCh; + if (!gpsState.flags.pvt) { // PVT is the prefered source + gpsSolDRV.numSat = _buffer.svinfo.numCh; + } + // TODO: populate satelites[] with sat info } break; case MSG_SIG_INFO: @@ -888,19 +891,59 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence - if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9 || gpsState.swVersionMajor > 23 || (gpsState.swVersionMajor == 23 && gpsState.swVersionMinor >=1)) { // > 23.01, don't use configureMSG - ubx_config_data8_payload_t rateValues[] = { - {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, - {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, - }; + if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9) { + // > 23.01, don't use configureMSG + if (gpsState.swVersionMajor > 23 || (gpsState.swVersionMajor == 23 && gpsState.swVersionMinor >= 1)) { + ubx_config_data8_payload_t rateValues[] = { + {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, + {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, + {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0}, + }; + + ubloxSendSetCfgBytes(rateValues, 5); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; + + // Try to enable SIG + ubloxSendSetCfgBytes(rateValues+5, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); + gpsState.flags.sig = _ack_state == UBX_ACK_GOT_ACK; + + // Try to enable SAT if SIG fails + rateValues[6].value = gpsState.flags.sig ? 0 : 1; + ubloxSendSetCfgBytes(rateValues+6, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); + gpsState.flags.sat = _ack_state == UBX_ACK_GOT_ACK ? rateValues[6].value : 0; + + } else { + configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + + configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + + configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + + configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - ubloxSendSetCfgBytes(rateValues, 7); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; + + configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + gpsState.flags.sat = 0; + + configureMSG(MSG_CLASS_UBX, MSG_SIG_INFO, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); + gpsState.flags.sig = _ack_state == UBX_ACK_GOT_ACK; + } if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz @@ -936,10 +979,21 @@ STATIC_PROTOTHREAD(gpsConfigure) configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK); + gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); ptWait(_ack_state == UBX_ACK_GOT_ACK); + // Needed for satelite information on older devices + configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || + _ack_state == UBX_ACK_GOT_NAK); + if (_ack_state == UBX_ACK_GOT_ACK) { + gpsState.flags.sat = 1; + } else { + gpsState.flags.sat = 0; + } + if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz } @@ -984,6 +1038,10 @@ STATIC_PROTOTHREAD(gpsConfigure) } } + DEBUG_SET(DEBUG_GPS, 5, gpsState.flags.pvt); + DEBUG_SET(DEBUG_GPS, 6, gpsState.flags.sat); + DEBUG_SET(DEBUG_GPS, 7, gpsState.flags.sig); + // Configure SBAS // If particular SBAS setting is not supported by the hardware we'll get a NAK, // however GPS would be functional. We are waiting for any response - ACK/NACK From d7e8525ac972513707bb73a72e6d02f4d7d45be8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 13:31:32 +0200 Subject: [PATCH 042/212] use version checks to pick NAV-SAT or NAV-SIG --- src/main/io/gps_ublox.c | 40 ++++++++++++++++++++++++++++++++-------- src/main/io/gps_ublox.h | 6 ++++++ 2 files changed, 38 insertions(+), 8 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 35b0de92ae6..a3bcb9379a4 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -893,7 +893,7 @@ STATIC_PROTOTHREAD(gpsConfigure) // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9) { // > 23.01, don't use configureMSG - if (gpsState.swVersionMajor > 23 || (gpsState.swVersionMajor == 23 && gpsState.swVersionMinor >= 1)) { + if (ubloxVersionGTE(23, 1)) { ubx_config_data8_payload_t rateValues[] = { {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, @@ -936,13 +936,12 @@ STATIC_PROTOTHREAD(gpsConfigure) ptWait(_ack_state == UBX_ACK_GOT_ACK); gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; - configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 0); + // NAV-SIG is available from 23.1 onwards, NAV-SAT from 15.0 to 23.1 + configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, ubloxVersionGTE(15,0)); ptWait(_ack_state == UBX_ACK_GOT_ACK); - gpsState.flags.sat = 0; + gpsState.flags.sat = ubloxVersionGTE(15, 0); - configureMSG(MSG_CLASS_UBX, MSG_SIG_INFO, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - gpsState.flags.sig = _ack_state == UBX_ACK_GOT_ACK; + gpsState.flags.sig = 0; } if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { @@ -984,6 +983,7 @@ STATIC_PROTOTHREAD(gpsConfigure) configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); ptWait(_ack_state == UBX_ACK_GOT_ACK); + //if(ubloxVersionGTE(15,0) && ubloxVersionLTE(23, 1)) // Needed for satelite information on older devices configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK || @@ -1053,7 +1053,7 @@ STATIC_PROTOTHREAD(gpsConfigure) if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX8) { gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); bool use_VALSET = 0; - if ( (gpsState.swVersionMajor > 23) || (gpsState.swVersionMajor == 23 && gpsState.swVersionMinor > 1) ) { + if (ubloxVersionGTE(23,1)) { use_VALSET = 1; } @@ -1063,7 +1063,7 @@ STATIC_PROTOTHREAD(gpsConfigure) configureGNSS(); } - ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); + ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); if(_ack_state == UBX_ACK_GOT_NAK) { gpsConfigMutable()->ubloxUseGalileo = SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT; @@ -1233,5 +1233,29 @@ const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index) return NULL; } +bool ubloxVersionLT(uint8_t mj2, uint8_t mn2) +{ + return gpsState.swVersionMajor < mj2 || (gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor < mn2); +} + +bool ubloxVersionGT(uint8_t mj2, uint8_t mn2) +{ + return gpsState.swVersionMajor > mj2 || (gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor > mn2); +} + +bool ubloxVersionGTE(uint8_t mj2, uint8_t mn2) +{ + return ubloxVersionGT(mj2, mn2) || ubloxVersionE(mj2, mn2); +} + +bool ubloxVersionLTE(uint8_t mj2, uint8_t mn2) +{ + return ubloxVersionLT(mj2, mn2) || ubloxVersionE(mj2, mn2); +} + +bool ubloxVersionE(uint8_t mj1, uint8_t mn1, uint8_t mj2, uint8_t mn2) +{ + return gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor == mn2; +} #endif diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 041f98653b5..959399ac600 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -469,6 +469,12 @@ bool isGpsUblox(void); const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index); +bool ubloxVersionLTE(uint8_t mj2, uint8_t mn2); +bool ubloxVersionLT(uint8_t mj2, uint8_t mn2); +bool ubloxVersionGT(uint8_t mj2, uint8_t mn2); +bool ubloxVersionGTE(uint8_t mj2, uint8_t mn2); +bool ubloxVersionE(uint8_t mj2, uint8_t mn2); + #ifdef __cplusplus } #endif From 8f7fe5bdff3851eae0c48b4aec210013f7551a23 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 13:44:00 +0200 Subject: [PATCH 043/212] missed on of the functions when remove parameters --- src/main/io/gps_ublox.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index a3bcb9379a4..7a8a5d198dd 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1253,7 +1253,7 @@ bool ubloxVersionLTE(uint8_t mj2, uint8_t mn2) return ubloxVersionLT(mj2, mn2) || ubloxVersionE(mj2, mn2); } -bool ubloxVersionE(uint8_t mj1, uint8_t mn1, uint8_t mj2, uint8_t mn2) +bool ubloxVersionE(uint8_t mj2, uint8_t mn2) { return gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor == mn2; } From 6de09006418cbb4cf75014bbb25cd7b4a3945bdd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 13:54:02 +0200 Subject: [PATCH 044/212] rename args --- src/main/io/gps_ublox.c | 20 ++++++++++---------- src/main/io/gps_ublox.h | 10 +++++----- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 7a8a5d198dd..0c582338020 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1233,29 +1233,29 @@ const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index) return NULL; } -bool ubloxVersionLT(uint8_t mj2, uint8_t mn2) +bool ubloxVersionLT(uint8_t mj, uint8_t mn) { - return gpsState.swVersionMajor < mj2 || (gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor < mn2); + return gpsState.swVersionMajor < mj || (gpsState.swVersionMajor == mj && gpsState.swVersionMinor < mn); } -bool ubloxVersionGT(uint8_t mj2, uint8_t mn2) +bool ubloxVersionGT(uint8_t mj, uint8_t mn) { - return gpsState.swVersionMajor > mj2 || (gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor > mn2); + return gpsState.swVersionMajor > mj || (gpsState.swVersionMajor == mj && gpsState.swVersionMinor > mn); } -bool ubloxVersionGTE(uint8_t mj2, uint8_t mn2) +bool ubloxVersionGTE(uint8_t mj, uint8_t mn) { - return ubloxVersionGT(mj2, mn2) || ubloxVersionE(mj2, mn2); + return ubloxVersionGT(mj, mn) || ubloxVersionE(mj, mn); } -bool ubloxVersionLTE(uint8_t mj2, uint8_t mn2) +bool ubloxVersionLTE(uint8_t mj, uint8_t mn) { - return ubloxVersionLT(mj2, mn2) || ubloxVersionE(mj2, mn2); + return ubloxVersionLT(mj, mn) || ubloxVersionE(mj, mn); } -bool ubloxVersionE(uint8_t mj2, uint8_t mn2) +bool ubloxVersionE(uint8_t mj, uint8_t mn) { - return gpsState.swVersionMajor == mj2 && gpsState.swVersionMinor == mn2; + return gpsState.swVersionMajor == mj && gpsState.swVersionMinor == mn; } #endif diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 959399ac600..b6e56845dac 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -469,11 +469,11 @@ bool isGpsUblox(void); const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index); -bool ubloxVersionLTE(uint8_t mj2, uint8_t mn2); -bool ubloxVersionLT(uint8_t mj2, uint8_t mn2); -bool ubloxVersionGT(uint8_t mj2, uint8_t mn2); -bool ubloxVersionGTE(uint8_t mj2, uint8_t mn2); -bool ubloxVersionE(uint8_t mj2, uint8_t mn2); +bool ubloxVersionLTE(uint8_t mj, uint8_t mn); +bool ubloxVersionLT(uint8_t mj, uint8_t mn); +bool ubloxVersionGT(uint8_t mj, uint8_t mn); +bool ubloxVersionGTE(uint8_t mj, uint8_t mn); +bool ubloxVersionE(uint8_t mj, uint8_t mn); #ifdef __cplusplus } From bd0a9b69423d5815d5436ade6c68bc6a78070740 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 26 Jun 2024 14:22:07 +0200 Subject: [PATCH 045/212] Separate gyro PT1 filter from LULU filter --- src/main/fc/settings.yaml | 2 +- src/main/sensors/gyro.c | 29 +++++++++++++++-------------- src/main/sensors/gyro.h | 8 ++++---- 3 files changed, 20 insertions(+), 19 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a27e9599db7..ff42fb18fa7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -192,7 +192,7 @@ tables: values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"] enum: led_pin_pwm_mode_e - name: gyro_filter_mode - values: ["STATIC", "DYNAMIC", "ADAPTIVE", "LULU"] + values: ["OFF", "STATIC", "DYNAMIC", "ADAPTIVE"] enum: gyroFilterType_e - name: headtracker_dev_type values: ["NONE", "SERIAL", "MSP"] diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index b4723f0da74..2f69b4d4657 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -96,7 +96,7 @@ EXTENDED_FASTRAM secondaryDynamicGyroNotchState_t secondaryDynamicGyroNotchState #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 11); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 12); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT, @@ -241,18 +241,13 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard return gyroHardware; } -static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t cutoff, uint32_t looptime, filterType_e filterType) +static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t cutoff, uint32_t looptime) { *applyFn = nullFilterApply; if (cutoff > 0) { for (int axis = 0; axis < 3; axis++) { - if(filterType == FILTER_LULU) { - luluFilterInit(&state[axis].lulu, cutoff); - *applyFn = (filterApplyFnPtr)luluFilterApply; - } else { - pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); - *applyFn = (filterApplyFnPtr)pt1FilterApply; - } + pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); + *applyFn = (filterApplyFnPtr)pt1FilterApply; } } } @@ -260,13 +255,19 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t static void gyroInitFilters(void) { //First gyro LPF running at full gyro frequency 8kHz - initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime(), FILTER_PT1); + initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime()); - if(gyroConfig()->gyroFilterMode == GYRO_FILTER_MODE_LULU) { - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyroLuluSampleCount, getLooptime(), FILTER_LULU); + /* + luluFilterInit(&state[axis].lulu, cutoff); + *applyFn = (filterApplyFnPtr)luluFilterApply; + + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyroLuluSampleCount, getLooptime(), FILTER_LULU); + */ + + if(gyroConfig()->gyroFilterMode != GYRO_FILTER_MODE_OFF) { + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime()); } else { - //Second gyro LPF runnig and PID frequency - this filter is dynamic when gyro_use_dyn_lpf = ON - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime(), FILTER_PT1); + gyroLpf2ApplyFn = nullFilterApply; } #ifdef USE_ADAPTIVE_FILTER diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 4b67081a5ae..c6f60b45bbb 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -53,10 +53,10 @@ typedef enum { } dynamicGyroNotchMode_e; typedef enum { - GYRO_FILTER_MODE_STATIC = 0, - GYRO_FILTER_MODE_DYNAMIC = 1, - GYRO_FILTER_MODE_ADAPTIVE = 2, - GYRO_FILTER_MODE_LULU = 3 + GYRO_FILTER_MODE_OFF = 0, + GYRO_FILTER_MODE_STATIC = 1, + GYRO_FILTER_MODE_DYNAMIC = 2, + GYRO_FILTER_MODE_ADAPTIVE = 3 } gyroFilterMode_e; typedef struct gyro_s { From b612e659a2a28e89b38e840d296052523f981518 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 15:24:03 +0200 Subject: [PATCH 046/212] First attempt at parsing signal info --- src/main/io/gps_ublox.c | 26 +++++++++++++++++++++----- src/main/io/gps_ublox.h | 23 +++++++++++------------ 2 files changed, 32 insertions(+), 17 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 0c582338020..e28dc6494f3 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -696,19 +696,35 @@ static bool gpsParseFrameUBLOX(void) if (_class == CLASS_NAV) { static int satInfoCount = 0; DEBUG_SET(DEBUG_GPS, 2, satInfoCount++); + DEBUG_SET(DEBUG_GPS, 3, _buffer.svinfo.numSvs); if (!gpsState.flags.pvt) { // PVT is the prefered source - gpsSolDRV.numSat = _buffer.svinfo.numCh; + gpsSolDRV.numSat = _buffer.svinfo.numSvs; } - // TODO: populate satelites[] with sat info + + for(int i =0; i < MIN(_buffer.svinfo.numSvs, UBLOX_MAX_SIGNALS); ++i) { + satelites[i].svId = _buffer.svinfo.channel[i].svId; + satelites[i].gnssId = _buffer.svinfo.channel[i].gnssId; + satelites[i].sigId = 0; + satelites[i].cno = _buffer.svinfo.channel[i].cno; + satelites[i].cno = _buffer.svinfo.channel[i].flags; + satelites[i].quality = _buffer.svinfo.channel[i].flags & 0x3; + satelites[i].sigFlags = (_buffer.svinfo.channel[i].flags >> 4 & 0x3); // Healthy, not healthy + //satelites[i].cno = _buffer.svinfo.channel[i].quality; + } + for(int i =_buffer.svinfo.numSvs; i < UBLOX_MAX_SIGNALS; ++i) { + satelites->svId = 0; + } + } break; case MSG_SIG_INFO: if (_class == CLASS_NAV && _buffer.navsig.version == 0) { static int sigInfoCount = 0; DEBUG_SET(DEBUG_GPS, 0, sigInfoCount++); + DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); if(_buffer.navsig.numSigs < UBLOX_MAX_SIGNALS) { - for(int i=0; i < UBLOX_MAX_SIGNALS && i < _buffer.navsig.numSigs; ++i) + for(int i=0; i < MIN(UBLOX_MAX_SIGNALS, _buffer.navsig.numSigs); ++i) { memcpy(&satelites[i], &_buffer.navsig.sig[i], sizeof(ubx_nav_sig_info)); } @@ -1245,12 +1261,12 @@ bool ubloxVersionGT(uint8_t mj, uint8_t mn) bool ubloxVersionGTE(uint8_t mj, uint8_t mn) { - return ubloxVersionGT(mj, mn) || ubloxVersionE(mj, mn); + return ubloxVersionE(mj, mn) || ubloxVersionGT(mj, mn); } bool ubloxVersionLTE(uint8_t mj, uint8_t mn) { - return ubloxVersionLT(mj, mn) || ubloxVersionE(mj, mn); + return ubloxVersionE(mj, mn) || ubloxVersionLT(mj, mn); } bool ubloxVersionE(uint8_t mj, uint8_t mn) diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index b6e56845dac..d887fe0d986 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -180,7 +180,7 @@ typedef struct { typedef struct { uint8_t gnssId; // gnssid 0 = GPS, 1 = SBAS, 2 = GALILEO, 3 = BEIDOU, 4 = IMES, 5 = QZSS, 6 = GLONASS uint8_t svId; // space vehicle ID - uint8_t sigId; // new style signal ID (gnssId:sigId) + uint8_t sigId; // signal ID uint8_t freqId; // 0-13 slot +, 0-13, glonass only int16_t prRes; // pseudo range residual (0.1m) uint8_t cno; // carrier to noise density ratio (dbHz) @@ -306,22 +306,21 @@ typedef struct { } ubx_nav_velned; typedef struct { - uint8_t chn; // Channel number, 255 for SVx not assigned to channel - uint8_t svid; // Satellite ID - uint8_t flags; // Bitmask - uint8_t quality; // Bitfield + uint8_t gnssId; // Channel number, 255 for SVx not assigned to channel + uint8_t svId; // Satellite ID uint8_t cno; // Carrier to Noise Ratio (Signal Strength) // dbHz, 0-55. - uint8_t elev; // Elevation in integer degrees - int16_t azim; // Azimuth in integer degrees - int32_t prRes; // Pseudo range residual in centimetres + int8_t elev; // Elevation in integer degrees +/-90 + int16_t azim; // Azimuth in integer degrees 0-360 + int16_t prRes; // Pseudo range residual in .1m + uint32_t flags; // Bitmask } ubx_nav_svinfo_channel; typedef struct { - uint32_t time; // GPS Millisecond time of week - uint8_t numCh; // Number of channels - uint8_t globalFlags; // Bitmask, Chip hardware generation 0:Antaris, 1:u-blox 5, 2:u-blox 6 + uint32_t itow; // GPS Millisecond time of week + uint8_t version; // Version = 0 + uint8_t numSvs; // (Space vehicle) Satelite count uint16_t reserved2; // Reserved - ubx_nav_svinfo_channel channel[16]; // 16 satellites * 12 byte + ubx_nav_svinfo_channel channel[UBLOX_MAX_SIGNALS]; // UBLOX_MAX_SIGNALS satellites * 12 byte } ubx_nav_svinfo; typedef struct { From e59a635117c4f04da971a3851b268c2574bcdc31 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 23:29:39 +0200 Subject: [PATCH 047/212] Simplify message rate setup. 2 cases: Firmware newer than 23.01 => has pvt and new setting message Everything else = legacy. (Including M8) --- src/main/io/gps_ublox.c | 175 +++++++++++----------------------------- 1 file changed, 49 insertions(+), 126 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index e28dc6494f3..9f312c1ec8f 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -607,8 +607,10 @@ static bool gpsParseFrameUBLOX(void) case MSG_PVT: { static int pvtCount = 0; - DEBUG_SET(DEBUG_GPS, 1, pvtCount++); + DEBUG_SET(DEBUG_GPS, 0, pvtCount++); } + + gpsState.flags.pvt = 1; next_fix_type = gpsMapFixType(_buffer.pvt.fix_status & NAV_STATUS_FIX_VALID, _buffer.pvt.fix_type); gpsSolDRV.fixType = next_fix_type; gpsSolDRV.llh.lon = _buffer.pvt.longitude; @@ -695,7 +697,8 @@ static bool gpsParseFrameUBLOX(void) case MSG_NAV_SAT: if (_class == CLASS_NAV) { static int satInfoCount = 0; - DEBUG_SET(DEBUG_GPS, 2, satInfoCount++); + gpsState.flags.sat = 1; + DEBUG_SET(DEBUG_GPS, 1, satInfoCount++); DEBUG_SET(DEBUG_GPS, 3, _buffer.svinfo.numSvs); if (!gpsState.flags.pvt) { // PVT is the prefered source gpsSolDRV.numSat = _buffer.svinfo.numSvs; @@ -720,8 +723,9 @@ static bool gpsParseFrameUBLOX(void) case MSG_SIG_INFO: if (_class == CLASS_NAV && _buffer.navsig.version == 0) { static int sigInfoCount = 0; - DEBUG_SET(DEBUG_GPS, 0, sigInfoCount++); + DEBUG_SET(DEBUG_GPS, 2, sigInfoCount++); DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); + gpsState.flags.sig = 1; if(_buffer.navsig.numSigs < UBLOX_MAX_SIGNALS) { for(int i=0; i < MIN(UBLOX_MAX_SIGNALS, _buffer.navsig.numSigs); ++i) @@ -749,6 +753,10 @@ static bool gpsParseFrameUBLOX(void) return false; } + DEBUG_SET(DEBUG_GPS, 5, gpsState.flags.pvt); + DEBUG_SET(DEBUG_GPS, 6, gpsState.flags.sat); + DEBUG_SET(DEBUG_GPS, 7, gpsState.flags.sig); + // we only return true when we get new position and speed data // this ensures we don't use stale data if (_new_position && _new_speed) { @@ -907,58 +915,23 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence - if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX9) { - // > 23.01, don't use configureMSG - if (ubloxVersionGTE(23, 1)) { + // > 23.01, don't use configureMSG, and have PVT + + if (ubloxVersionGTE(23, 1)) { ubx_config_data8_payload_t rateValues[] = { - {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, - {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, - {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, - {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0}, + {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, // 0 + {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, // 1 + {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, // 2 + {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, // 3 + {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, // 4 + {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, // 5 + {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0} // 6 }; - ubloxSendSetCfgBytes(rateValues, 5); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; - // Try to enable SIG - ubloxSendSetCfgBytes(rateValues+5, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - gpsState.flags.sig = _ack_state == UBX_ACK_GOT_ACK; + ubloxSendSetCfgBytes(rateValues, 7); + ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); - // Try to enable SAT if SIG fails - rateValues[6].value = gpsState.flags.sig ? 0 : 1; - ubloxSendSetCfgBytes(rateValues+6, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - gpsState.flags.sat = _ack_state == UBX_ACK_GOT_ACK ? rateValues[6].value : 0; - - } else { - configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; - - // NAV-SIG is available from 23.1 onwards, NAV-SAT from 15.0 to 23.1 - configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, ubloxVersionGTE(15,0)); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - gpsState.flags.sat = ubloxVersionGTE(15, 0); - - gpsState.flags.sig = 0; - } if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz @@ -972,91 +945,41 @@ STATIC_PROTOTHREAD(gpsConfigure) configureRATE(hz2rate(5)); // 5Hz ptWait(_ack_state == UBX_ACK_GOT_ACK); } - } - else { - // u-Blox 5/6/7/8 or unknown - // u-Blox 7-8 support PVT - if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7) { - configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_SOL, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + } else { + configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_STATUS, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - gpsState.flags.pvt = _ack_state == UBX_ACK_GOT_ACK; + configureMSG(MSG_CLASS_UBX, MSG_SOL, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_VELNED, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - //if(ubloxVersionGTE(15,0) && ubloxVersionLTE(23, 1)) - // Needed for satelite information on older devices - configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK || - _ack_state == UBX_ACK_GOT_NAK); - if (_ack_state == UBX_ACK_GOT_ACK) { - gpsState.flags.sat = 1; - } else { - gpsState.flags.sat = 0; - } + configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 10); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { - configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz - } - else { - configureRATE(hz2rate(5)); // 5Hz - } - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - - if(_ack_state == UBX_ACK_GOT_NAK) { // Fallback to safe 5Hz in case of error - configureRATE(hz2rate(5)); // 5Hz - ptWait(_ack_state == UBX_ACK_GOT_ACK); - } - } - // u-Blox 5/6 doesn't support PVT, use legacy config - // UNKNOWN also falls here, use as a last resort - else { - configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_STATUS, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + // Protocol < 23.01 does not have MSG_PVT + //configureMSG(MSG_CLASS_UBX, MSG_PVT, 0); + //ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - configureMSG(MSG_CLASS_UBX, MSG_SOL, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_VELNED, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 10); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - - // This may fail on old UBLOX units, advance forward on both ACK and NAK - configureMSG(MSG_CLASS_UBX, MSG_PVT, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); + // This may fail on old UBLOX units, advance forward on both ACK and NAK + configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - // Configure data rate to 5HZ - configureRATE(200); - ptWait(_ack_state == UBX_ACK_GOT_ACK); - } - } + // Configure data rate to 5HZ + configureRATE(hz2rate(5)); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + }// end message config - DEBUG_SET(DEBUG_GPS, 5, gpsState.flags.pvt); - DEBUG_SET(DEBUG_GPS, 6, gpsState.flags.sat); - DEBUG_SET(DEBUG_GPS, 7, gpsState.flags.sig); + gpsState.flags.pvt = 0; + gpsState.flags.sat = 0; + gpsState.flags.sig = 0; // Configure SBAS // If particular SBAS setting is not supported by the hardware we'll get a NAK, From d0781576ad08bbf912e7051c38d24f3a985c03ac Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 26 Jun 2024 23:43:42 +0200 Subject: [PATCH 048/212] Still simpler, but 3 cases. 1) New api, nav_pvt and nav_sig (m9+) 2) Old api, nav_pvt and nav_sat (m7?/m8) 3) Old api, no nav_pvt or nav_sat (time to upgrade) --- src/main/io/gps_ublox.c | 79 +++++++++++++++++++++++------------------ 1 file changed, 44 insertions(+), 35 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 9f312c1ec8f..f3fd3506c90 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -915,37 +915,44 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence - // > 23.01, don't use configureMSG, and have PVT + if (ubloxVersionGTE(23, 1)) { // M9+, new setting API, PVT and NAV_SIG + ubx_config_data8_payload_t rateValues[] = { + {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, // 0 + {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, // 1 + {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, // 2 + {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, // 3 + {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, // 4 + {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, // 5 + {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0} // 6 + }; - if (ubloxVersionGTE(23, 1)) { - ubx_config_data8_payload_t rateValues[] = { - {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, // 0 - {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, // 1 - {UBLOX_CFG_MSGOUT_NAV_VELNED_UART1, 0}, // 2 - {UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1, 0}, // 3 - {UBLOX_CFG_MSGOUT_NAV_PVT_UART1, 1}, // 4 - {UBLOX_CFG_MSGOUT_NAV_SIG_UART1, 1}, // 5 - {UBLOX_CFG_MSGOUT_NAV_SAT_UART1, 0} // 6 - }; + ubloxSendSetCfgBytes(rateValues, 7); + ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); + } else if(ubloxVersionGTE(15,0)) { // M8 and potentially M7, PVT, NAV_SAT, old setting API + configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_STATUS, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - ubloxSendSetCfgBytes(rateValues, 7); - ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); + configureMSG(MSG_CLASS_UBX, MSG_SOL, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_UBX, MSG_VELNED, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { - configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz - } else { - configureRATE(hz2rate(5)); // 5Hz - gpsConfigMutable()->ubloxNavHz = SETTING_GPS_UBLOX_NAV_HZ_DEFAULT; - } + configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + + configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + + configureMSG(MSG_CLASS_UBX, MSG_PVT, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - if(_ack_state == UBX_ACK_GOT_NAK) { // Fallback to safe 5Hz in case of error - configureRATE(hz2rate(5)); // 5Hz - ptWait(_ack_state == UBX_ACK_GOT_ACK); - } - } else { + configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); + } else { // Really old stuff, consider upgrading :), ols setting API, no PVT or NAV_SAT or NAV_SIG configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK); @@ -961,21 +968,23 @@ STATIC_PROTOTHREAD(gpsConfigure) configureMSG(MSG_CLASS_UBX, MSG_TIMEUTC, 10); ptWait(_ack_state == UBX_ACK_GOT_ACK); - // Protocol < 23.01 does not have MSG_PVT - //configureMSG(MSG_CLASS_UBX, MSG_PVT, 0); - //ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - - // This may fail on old UBLOX units, advance forward on both ACK and NAK - configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); - ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - configureMSG(MSG_CLASS_UBX, MSG_SVINFO, 0); ptWait(_ack_state == UBX_ACK_GOT_ACK); + }// end message config + + if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { + configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz + } else { + configureRATE(hz2rate(5)); // 5Hz + gpsConfigMutable()->ubloxNavHz = SETTING_GPS_UBLOX_NAV_HZ_DEFAULT; + } + ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); - // Configure data rate to 5HZ - configureRATE(hz2rate(5)); + if(_ack_state == UBX_ACK_GOT_NAK) { // Fallback to safe 5Hz in case of error + configureRATE(hz2rate(5)); // 5Hz ptWait(_ack_state == UBX_ACK_GOT_ACK); - }// end message config + } + gpsState.flags.pvt = 0; gpsState.flags.sat = 0; From 9ad5252bc9523690c7949f927e33de0abf135ef2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 27 Jun 2024 01:02:10 +0200 Subject: [PATCH 049/212] Disable nmed with new api for swversion >23.1 --- src/main/io/gps_ublox.c | 39 ++++++++++++++++++++++++++------------- src/main/io/gps_ublox.h | 5 +++++ 2 files changed, 31 insertions(+), 13 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index f3fd3506c90..a3065f73daa 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -890,26 +890,38 @@ STATIC_PROTOTHREAD(gpsConfigure) } ptWait(_ack_state == UBX_ACK_GOT_ACK); - // Disable NMEA messages gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); + // Disable NMEA messages + if (ubloxVersionGTE(23, 1)) { + ubx_config_data8_payload_t nmeaValues[] = { + { UBLOX_CFG_MSGOUT_NMEA_ID_GGA_UART1, 0 }, + { UBLOX_CFG_MSGOUT_NMEA_ID_GLL_UART1, 0 }, + { UBLOX_CFG_MSGOUT_NMEA_ID_GSA_UART1, 0 }, + { UBLOX_CFG_MSGOUT_NMEA_ID_RMC_UART1, 0 }, + { UBLOX_CFG_MSGOUT_NMEA_ID_VTG_UART1, 0 }, + }; - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GGA, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + ubloxSendSetCfgBytes(nmeaValues, 5); + ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK), GPS_CFG_CMD_TIMEOUT_MS); + } else { + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GGA, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GLL, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GLL, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GSA, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GSA, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GSV, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_GSV, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_RMC, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_RMC, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); - configureMSG(MSG_CLASS_NMEA, MSG_NMEA_VGS, 0); - ptWait(_ack_state == UBX_ACK_GOT_ACK); + configureMSG(MSG_CLASS_NMEA, MSG_NMEA_VGS, 0); + ptWait(_ack_state == UBX_ACK_GOT_ACK); + } // Configure UBX binary messages gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); @@ -972,6 +984,7 @@ STATIC_PROTOTHREAD(gpsConfigure) ptWait(_ack_state == UBX_ACK_GOT_ACK); }// end message config + ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_SHORT_TIMEOUT); if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz } else { diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index d887fe0d986..c79c4654292 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -63,6 +63,11 @@ extern "C" { #define UBLOX_CFG_MSGOUT_NAV_VELNED_UART1 0x20910043 // U1 #define UBLOX_CFG_MSGOUT_NAV_TIMEUTC_UART1 0x2091005c // U1 #define UBLOX_CFG_MSGOUT_NAV_PVT_UART1 0x20910007 // U1 +#define UBLOX_CFG_MSGOUT_NMEA_ID_GGA_UART1 0x209100bb // U1 +#define UBLOX_CFG_MSGOUT_NMEA_ID_GLL_UART1 0x209100ca // U1 +#define UBLOX_CFG_MSGOUT_NMEA_ID_GSA_UART1 0x209100c0 // U1 +#define UBLOX_CFG_MSGOUT_NMEA_ID_RMC_UART1 0x209100ac // U1 +#define UBLOX_CFG_MSGOUT_NMEA_ID_VTG_UART1 0x209100b1 // U1 #define UBLOX_CFG_SIGNAL_SBAS_ENA 0x10310020 // U1 #define UBLOX_CFG_SIGNAL_SBAS_L1CA_ENA 0x10310005 // U1 From c9fc18f8e9eaf9d77d836c6411515cb9cf3add75 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 27 Jun 2024 01:42:59 +0200 Subject: [PATCH 050/212] use 0xff as no sat. --- src/main/fc/cli.c | 4 ++-- src/main/io/gps_ublox.c | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index fa8ec75b615..fe54e175b27 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4396,11 +4396,11 @@ static void cliUbloxPrintSatelites(char *arg) for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) { const ubx_nav_sig_info *sat = gpsGetUbloxSatelite(i); - if(sat == NULL || sat->svId == 0) { + if(sat == NULL) { continue; } - cliPrintLinef("satelite: %d:%d", sat->gnssId, sat->svId); + cliPrintLinef("satelite[%d]: %d:%d", i+1, sat->gnssId, sat->svId); cliPrintLinef("sigId: %d (%s)", sat->sigId, _ubloxGetSigId(sat->gnssId, sat->sigId)); cliPrintLinef("signal strength: %i dbHz", sat->cno); cliPrintLinef("quality: %i (%s)", sat->quality, _ubloxGetQuality(sat->quality)); diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index a3065f73daa..93395e7d1d4 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -726,7 +726,7 @@ static bool gpsParseFrameUBLOX(void) DEBUG_SET(DEBUG_GPS, 2, sigInfoCount++); DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); gpsState.flags.sig = 1; - if(_buffer.navsig.numSigs < UBLOX_MAX_SIGNALS) + if(_buffer.navsig.numSigs > 0) { for(int i=0; i < MIN(UBLOX_MAX_SIGNALS, _buffer.navsig.numSigs); ++i) { @@ -734,7 +734,7 @@ static bool gpsParseFrameUBLOX(void) } for(int i = _buffer.navsig.numSigs; i < UBLOX_MAX_SIGNALS; ++i) { - satelites[i].svId = 0; // no used + satelites[i].svId = 0xFF; // no used } } } @@ -1187,7 +1187,7 @@ bool isGpsUblox(void) const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index) { - if(index < UBLOX_MAX_SIGNALS) { + if(index < UBLOX_MAX_SIGNALS && satelites[index].svId != 0xFF) { return &satelites[index]; } From 2bca68bdca1f59fb5ae117c85528b3f3813166fd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 27 Jun 2024 21:45:37 +0200 Subject: [PATCH 051/212] make sure to init satelites as not used --- src/main/io/gps_ublox.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 93395e7d1d4..679bcf91e33 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1033,6 +1033,11 @@ STATIC_PROTOTHREAD(gpsConfigure) } } + for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) + { + satelites[i].svId = 0xFF; + } + ptEnd(0); } From f8cc253b4c37bc5ca7ca8fe2f44a71991fe4b1b2 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 28 Jun 2024 12:50:02 +0200 Subject: [PATCH 052/212] LuLu filter as separate entity --- src/main/sensors/gyro.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 2f69b4d4657..780bada378d 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -88,6 +88,9 @@ STATIC_FASTRAM filter_t gyroLpfState[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr gyroLpf2ApplyFn; STATIC_FASTRAM filter_t gyroLpf2State[XYZ_AXIS_COUNT]; +STATIC_FASTRAM filterApplyFnPtr gyroLuluApplyFn; +STATIC_FASTRAM filter_t gyroLuluState[XYZ_AXIS_COUNT]; + #ifdef USE_DYNAMIC_FILTERS EXTENDED_FASTRAM gyroAnalyseState_t gyroAnalyseState; From e05c38fbcbf30b0708c93b835d712b05992ff663 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 29 Jun 2024 12:12:19 +0200 Subject: [PATCH 053/212] Add some docs on Serial Gimbal --- docs/Serial Gimbal.mb | 33 +++++++++++++++++++++++++++++++++ 1 file changed, 33 insertions(+) create mode 100644 docs/Serial Gimbal.mb diff --git a/docs/Serial Gimbal.mb b/docs/Serial Gimbal.mb new file mode 100644 index 00000000000..795cb5490a4 --- /dev/null +++ b/docs/Serial Gimbal.mb @@ -0,0 +1,33 @@ +# Serial Gimbal +INAV 8.0 introduces support for serial Gimbals. Currently, it is compatible with the protocol used by the Walksnail GM series gimbals. + +While these gimbals also support PWM as input, using the Serial protocol gives it more flexibility and saves up to 4 PWM channels. The downside of the Serial protocol vs PWM input is that you don't have access to the full power of INAV's mixers. The main advantage is that you gain easy control of gimbal functions using INAV's modes. + +# Axis Input +The Serial Gimbal supports 2 differents inputs. + +## PWM Channels +This is the simplest way to control the Gimbal, and just lets the Gimbal use the value of a given RC PWM Channel. You can control all 3 gimbal axis, plust the Gimbal sensitivity. Unlike the raw PWM input, modes are controlled by INAV modes, instead of a PWM channels. If an rc channel is set to 0, that input will be ignore. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab. +Since it is using rc channels as inputs, you can have a mixer in your radio and setup a head tracker in the traditional way, like you would with home made servo gimbal. + +## Headtracker Input +Headtracker input is only used when you have a Headtracker device configured and the ```Gimbal Headtracker``` mode is active. +A Headtracker device is a device that transmits headtracker information by a side channel, instead of relying on your rc link. + +In head tracker mode, the Serial Gimbal will ignore the axis rc channel inputs and replace it with the inputs coming from the Headtracker device. + +# Gimbal Modes +## No Gimbal mode selected +Like ACRO is the default mode for flight modes, the Gimbal will default to ```FPV Mode``` or ```Follow Mode``` when no mode is selected. The gimbal will try to stablized the footag and will follow the aircraft pitch, roll and yaw movements and use user inputs to point the camera where the user wants. + +## Gimbal Center +This locks the gimbal camera to the center position and ignores any user input. Useful to reset the camera if you loose orientation. + +## Gimbal Headtracker +Switches inputs to the configured Headtracker device. If no device is configured it will behave like Gimbal Center. + +## Gimbal Level Tilt +This mode locks the camera tilt (pitch axis) and keeps it level with the horizon. Pitching the aircraft up and down, will move the camera so it stays pointing at the horizon. It can be combined with ```Gimbal Level Roll```. + +## Gimbal Level Roll +This mode locks the camera roll and keeps it level with the horizon. Rolling the aircraft will move the camera so it stays level with the horizon. It can be combined with ```Gimbal Level Tilt```. From 17729ed230477c81bc920bc3a79a031fc959de62 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 29 Jun 2024 12:17:43 +0200 Subject: [PATCH 054/212] Oops... --- docs/{Serial Gimbal.mb => Serial Gimbal.md} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename docs/{Serial Gimbal.mb => Serial Gimbal.md} (100%) diff --git a/docs/Serial Gimbal.mb b/docs/Serial Gimbal.md similarity index 100% rename from docs/Serial Gimbal.mb rename to docs/Serial Gimbal.md From a9cdb7456008b22d40c88d11545c691df16a580c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 29 Jun 2024 12:26:37 +0200 Subject: [PATCH 055/212] More changes --- docs/Serial Gimbal.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/docs/Serial Gimbal.md b/docs/Serial Gimbal.md index 795cb5490a4..7b1b20a1bb4 100644 --- a/docs/Serial Gimbal.md +++ b/docs/Serial Gimbal.md @@ -7,8 +7,7 @@ While these gimbals also support PWM as input, using the Serial protocol gives i The Serial Gimbal supports 2 differents inputs. ## PWM Channels -This is the simplest way to control the Gimbal, and just lets the Gimbal use the value of a given RC PWM Channel. You can control all 3 gimbal axis, plust the Gimbal sensitivity. Unlike the raw PWM input, modes are controlled by INAV modes, instead of a PWM channels. If an rc channel is set to 0, that input will be ignore. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab. -Since it is using rc channels as inputs, you can have a mixer in your radio and setup a head tracker in the traditional way, like you would with home made servo gimbal. +This is the simplest way to control the Gimbal, as you can use your radio mixer and sliders to Control the gimbal by assigning RC channels to functions in the ```Configuration``` tab. You can control all 3 gimbal axis, plust the Gimbal sensitivity. Unlike the raw PWM input, gimbal modes are controlled by INAV modes and you can control roll channel as well, instead of wiring 4 servo outputs. If an rc channel is set to 0, that input will be ignore and will be equivalent to a centered RC channel. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab. ## Headtracker Input Headtracker input is only used when you have a Headtracker device configured and the ```Gimbal Headtracker``` mode is active. From dc3e723ccdf0d93f213a3a8c2ad17f40f67a48ec Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 29 Jun 2024 06:45:14 -0400 Subject: [PATCH 056/212] Update Serial Gimbal.md --- docs/Serial Gimbal.md | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/docs/Serial Gimbal.md b/docs/Serial Gimbal.md index 7b1b20a1bb4..984e00f29d1 100644 --- a/docs/Serial Gimbal.md +++ b/docs/Serial Gimbal.md @@ -7,7 +7,7 @@ While these gimbals also support PWM as input, using the Serial protocol gives i The Serial Gimbal supports 2 differents inputs. ## PWM Channels -This is the simplest way to control the Gimbal, as you can use your radio mixer and sliders to Control the gimbal by assigning RC channels to functions in the ```Configuration``` tab. You can control all 3 gimbal axis, plust the Gimbal sensitivity. Unlike the raw PWM input, gimbal modes are controlled by INAV modes and you can control roll channel as well, instead of wiring 4 servo outputs. If an rc channel is set to 0, that input will be ignore and will be equivalent to a centered RC channel. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab. +This is the simplest way to control the Gimbal, as you can use your radio mixer and sliders to Control the gimbal by assigning RC channels to functions in the ```Configuration``` tab. You can control all 3 gimbal axis and unlike the raw PWM input, gimbal modes are controlled by INAV modes and you can control roll channel as well, instead of wiring 4 servo outputs. If an rc channel is set to 0, that input will be ignore and will be equivalent to a centered RC channel. So, if you setup the serial gimbal and don't assign any rc channels, it will stay centered, with default sensitivity and will obey the Gimbal MODES setup in the Modes tab. ## Headtracker Input Headtracker input is only used when you have a Headtracker device configured and the ```Gimbal Headtracker``` mode is active. @@ -30,3 +30,27 @@ This mode locks the camera tilt (pitch axis) and keeps it level with the horizon ## Gimbal Level Roll This mode locks the camera roll and keeps it level with the horizon. Rolling the aircraft will move the camera so it stays level with the horizon. It can be combined with ```Gimbal Level Tilt```. + +# Advanced settings +The gimbal also supports some advanced settings not exposed in the configurator. + +## Gimbal Trim +You can set a trim setting for the gimbal, the idea is that it will shift the notion of center of the gimbal, like a trim and let you setup a fixed camera up tilt, like you would have in a traditional fpv quad setup. + +``` +gimbal_pan_trim = 0 +Allowed range: -500 - 500 + +gimbal_tilt_trim = 0 +Allowed range: -500 - 500 + +gimbal_roll_trim = 0 +Allowed range: -500 - 500 +``` + +## Gimbal and Headtracker on a single uart +As INAV does not process any inputs from the Walksnail Gimbal, it is possible to share the uard with the Walksnail Headtracking output by connect the fc TX to the gimbal and RX to receive the headtracker input. +``` +gimbal_serial_single_uart = OFF +Allowed values: OFF, ON +``` From 817981fa4b4c3d9ba6bb4a6975b799057dba9b9c Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 29 Jun 2024 13:43:10 +0100 Subject: [PATCH 057/212] add flown loiter radius for fixed wing --- src/main/navigation/navigation.c | 9 ++- src/main/navigation/navigation.h | 1 + src/main/programming/logic_condition.c | 105 +++++++++++++------------ src/main/programming/logic_condition.h | 1 + 4 files changed, 65 insertions(+), 51 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 6eed742e804..f7c7303d138 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -5074,5 +5074,12 @@ bool canFwLandingBeCancelled(void) { return FLIGHT_MODE(NAV_FW_AUTOLAND) && posControl.navState != NAV_STATE_FW_LANDING_FLARE; } - #endif +uint16_t getFlownLoiterRadius(void) +{ + if (STATE(AIRPLANE) && navGetCurrentStateFlags() & NAV_CTL_HOLD) { + return CENTIMETERS_TO_METERS(calculateDistanceToDestination(&posControl.desiredState.pos)); + } + + return 0; +} diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 101b41cd637..1b7734c8b13 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -694,6 +694,7 @@ bool rthAltControlStickOverrideCheck(uint8_t axis); int8_t navCheckActiveAngleHoldAxis(void); uint8_t getActiveWpNumber(void); +uint16_t getFlownLoiterRadius(void); /* Returns the heading recorded when home position was acquired. * Note that the navigation system uses deg*100 as unit and angles diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index f927ac18d1b..6e43d2394cd 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -97,7 +97,7 @@ static int logicConditionCompute( int temporaryValue; #if defined(USE_VTX_CONTROL) vtxDeviceCapability_t vtxDeviceCapability; -#endif +#endif switch (operation) { @@ -154,7 +154,7 @@ static int logicConditionCompute( case LOGIC_CONDITION_NOR: return !(operandA || operandB); - break; + break; case LOGIC_CONDITION_NOT: return !operandA; @@ -170,7 +170,7 @@ static int logicConditionCompute( return false; } - //When both operands are not met, keep current value + //When both operands are not met, keep current value return currentValue; break; @@ -238,7 +238,7 @@ static int logicConditionCompute( gvSet(operandA, operandB); return operandB; break; - + case LOGIC_CONDITION_GVAR_INC: temporaryValue = gvGet(operandA) + operandB; gvSet(operandA, temporaryValue); @@ -270,7 +270,7 @@ static int logicConditionCompute( return operandA; } break; - + case LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY: LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY); return true; @@ -293,12 +293,12 @@ static int logicConditionCompute( ENABLE_STATE(CALIBRATE_MAG); return true; break; -#endif +#endif case LOGIC_CONDITION_SET_VTX_POWER_LEVEL: -#if defined(USE_VTX_CONTROL) +#if defined(USE_VTX_CONTROL) #if(defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)) if ( - logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) ) { logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] = constrain(operandA, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); @@ -346,18 +346,18 @@ static int logicConditionCompute( LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH); return true; break; - + case LOGIC_CONDITION_INVERT_YAW: LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW); return true; break; - + case LOGIC_CONDITION_OVERRIDE_THROTTLE: logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE] = operandA; LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE); return operandA; break; - + case LOGIC_CONDITION_SET_OSD_LAYOUT: logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT] = operandA; LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT); @@ -373,18 +373,18 @@ static int logicConditionCompute( case LOGIC_CONDITION_SIN: temporaryValue = (operandB == 0) ? 500 : operandB; - return sin_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + return sin_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; break; - + case LOGIC_CONDITION_COS: temporaryValue = (operandB == 0) ? 500 : operandB; - return cos_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + return cos_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; break; break; - + case LOGIC_CONDITION_TAN: temporaryValue = (operandB == 0) ? 500 : operandB; - return tan_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + return tan_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; break; case LOGIC_CONDITION_MIN: @@ -394,11 +394,11 @@ static int logicConditionCompute( case LOGIC_CONDITION_MAX: return (operandA > operandB) ? operandA : operandB; break; - + case LOGIC_CONDITION_MAP_INPUT: return scaleRange(constrain(operandA, 0, operandB), 0, operandB, 0, 1000); break; - + case LOGIC_CONDITION_MAP_OUTPUT: return scaleRange(constrain(operandA, 0, 1000), 0, 1000, 0, operandB); break; @@ -507,7 +507,7 @@ static int logicConditionCompute( default: return false; - break; + break; } } @@ -516,7 +516,7 @@ void logicConditionProcess(uint8_t i) { const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); if (logicConditions(i)->enabled && activatorValue && !cliMode) { - + /* * Process condition only when latch flag is not set * Latched LCs can only go from OFF to ON, not the other way @@ -525,13 +525,13 @@ void logicConditionProcess(uint8_t i) { const int operandAValue = logicConditionGetOperandValue(logicConditions(i)->operandA.type, logicConditions(i)->operandA.value); const int operandBValue = logicConditionGetOperandValue(logicConditions(i)->operandB.type, logicConditions(i)->operandB.value); const int newValue = logicConditionCompute( - logicConditionStates[i].value, - logicConditions(i)->operation, - operandAValue, + logicConditionStates[i].value, + logicConditions(i)->operation, + operandAValue, operandBValue, i ); - + logicConditionStates[i].value = newValue; /* @@ -606,7 +606,7 @@ static int logicConditionGetWaypointOperandValue(int operand) { return distance; } break; - + case LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION: return (NAV_Status.activeWpIndex > 0) ? ((posControl.waypointList[NAV_Status.activeWpIndex-1].p3 & NAV_WP_USER1) == NAV_WP_USER1) : 0; break; @@ -652,11 +652,11 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER: // in s return constrain((uint32_t)getFlightTime(), 0, INT16_MAX); break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE: //in m return constrain(GPS_distanceToHome, 0, INT16_MAX); break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE: //in m return constrain(getTotalTravelDistance() / 100, 0, INT16_MAX); break; @@ -664,7 +664,7 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_RSSI: return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_VBAT: // V / 100 return getBatteryVoltage(); break; @@ -680,7 +680,7 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT: // Amp / 100 return getAmperage(); break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN: // mAh return getMAhDrawn(); break; @@ -697,7 +697,7 @@ static int logicConditionGetFlightOperandValue(int operand) { return gpsSol.numSat; } break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID: // 0/1 return STATE(GPS_FIX) ? 1 : 0; break; @@ -749,15 +749,15 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH: // 0/1 return (navGetCurrentStateFlags() & NAV_CTL_LAUNCH) ? 1 : 0; - break; - + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL: // 0/1 return (navGetCurrentStateFlags() & NAV_CTL_ALT) ? 1 : 0; - break; + break; case LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL: // 0/1 return (navGetCurrentStateFlags() & NAV_CTL_POS) ? 1 : 0; - break; + break; case LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING: // 0/1 return (navGetCurrentStateFlags() & NAV_CTL_EMERG) ? 1 : 0; @@ -765,7 +765,7 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH: // 0/1 return (navGetCurrentStateFlags() & NAV_AUTO_RTH) ? 1 : 0; - break; + break; case LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING: // 0/1 #ifdef USE_FW_AUTOLAND @@ -773,22 +773,22 @@ static int logicConditionGetFlightOperandValue(int operand) { #else return ((navGetCurrentStateFlags() & NAV_CTL_LAND)) ? 1 : 0; #endif - + break; case LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE: // 0/1 return (failsafePhase() != FAILSAFE_IDLE) ? 1 : 0; break; - - case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW: // + + case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW: // return axisPID[YAW]; break; - - case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL: // + + case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL: // return axisPID[ROLL]; break; - - case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH: // + + case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH: // return axisPID[PITCH]; break; @@ -819,7 +819,7 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE: //int return getConfigBatteryProfile() + 1; break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int return currentMixerProfileIndex + 1; break; @@ -830,15 +830,20 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: return getLoiterRadius(navConfig()->fw.loiter_radius); + break; + + case LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS: + return getFlownLoiterRadius(); + break; case LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS: return isEstimatedAglTrusted(); break; - + case LOGIC_CONDITION_OPERAND_FLIGHT_AGL: return getEstimatedAglPosition(); - break; - + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW: return rangefinderGetLatestRawAltitude(); break; @@ -946,7 +951,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) { //Extract RC channel raw value if (operand >= 1 && operand <= MAX_SUPPORTED_RC_CHANNEL_COUNT) { retVal = rxGetChannelValue(operand - 1); - } + } break; case LOGIC_CONDITION_OPERAND_TYPE_FLIGHT: @@ -974,7 +979,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) { retVal = programmingPidGetOutput(operand); } break; - + case LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS: retVal = logicConditionGetWaypointOperandValue(operand); break; @@ -988,7 +993,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) { /* * conditionId == -1 is always evaluated as true - */ + */ int logicConditionGetValue(int8_t conditionId) { if (conditionId >= 0) { return logicConditionStates[conditionId].value; @@ -1070,7 +1075,7 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) { uint32_t getLoiterRadius(uint32_t loiterRadius) { #ifdef USE_PROGRAMMING_FRAMEWORK - if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && !(FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding())) { return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); } else { diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 5defafaee67..25d6a5a9e1f 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -143,6 +143,7 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW, // deg // 40 LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE, // 41 LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE, // int // 42 + LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS, // 43 } logicFlightOperands_e; typedef enum { From 698ecad29b6695ad3404b9b5cc20035eead12787 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 29 Jun 2024 17:17:51 +0100 Subject: [PATCH 058/212] Update Programming Framework.md --- docs/Programming Framework.md | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index 4eb7744e54e..b2ce6fe3b93 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -1,10 +1,10 @@ # INAV Programming Framework -INAV Programming Framework (IPF) is a mechanism that allows you to to create +INAV Programming Framework (IPF) is a mechanism that allows you to to create custom functionality in INAV. You can choose for certain actions to be done, based on custom conditions you select. -Logic conditions can be based on things such as RC channel values, switches, altitude, +Logic conditions can be based on things such as RC channel values, switches, altitude, distance, timers, etc. The conditions you create can also make use of other conditions you've entered previously. The results can be used in: @@ -56,8 +56,8 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn | 9 | XOR | `true` if `Operand A` or `Operand B` is `true`, but not both | | 10 | NAND | `false` if `Operand A` and `Operand B` are both `true`| | 11 | NOR | `true` if `Operand A` and `Operand B` are both `false` | -| 12 | NOT | The boolean opposite to `Operand A` | -| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`| +| 12 | NOT | The boolean opposite to `Operand A` | +| 13 | Sticky | `Operand A` is the activation operator, `Operand B` is the deactivation operator. After the activation is `true`, the operator will return `true` until Operand B is evaluated as `true`| | 14 | Basic: Add | Add `Operand A` to `Operand B` and returns the result | | 15 | Basic: Subtract | Substract `Operand B` from `Operand A` and returns the result | | 16 | Basic: Multiply | Multiply `Operand A` by `Operand B` and returns the result | @@ -147,7 +147,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn | 26 | Stabilized Pitch | Pitch PID controller output `[-500:500]` | | 27 | Stabilized Yaw | Yaw PID controller output `[-500:500]` | | 28 | 3D home distance [m] | 3D distance to home in `meters`. Calculated from Home distance and Altitude using Pythagorean theorem | -| 29 | CRSF LQ | Link quality as returned by the CRSF protocol | +| 29 | CRSF LQ | Link quality as returned by the CRSF protocol | | 30 | CRSF SNR | SNR as returned by the CRSF protocol | | 31 | GPS Valid Fix | Boolean `0`/`1`. True when the GPS has a valid 3D Fix | | 32 | Loiter Radius [cm] | The current loiter radius in cm. | @@ -161,6 +161,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn | 40 | Yaw [deg] | Current heading (yaw) in `degrees` | | 41 | FW Land Sate | Integer `1` - `5`, indicates the status of the FW landing, 0 Idle, 1 Downwind, 2 Base Leg, 3 Final Approach, 4 Glide, 5 Flare | | 42 | Current battery profile | The active battery profile. Integer `[1..MAX_PROFILE_COUNT]` | +| 43 | Flown Loiter Radius [m] | The actual loiter radius flown by a fixed wing during hold modes, in `meters` | #### FLIGHT_MODE @@ -183,7 +184,7 @@ The flight mode operands return `true` when the mode is active. These are modes | 12 | USER 3 | `true` when the **USER 3** mode is active. | | 13 | USER 4 | `true` when the **USER 4** mode is active. | | 14 | Acro | `true` when you are in the **Acro** flight mode. | -| 15 | Waypoint Mission | `true` when you are in the **WP Mission** flight mode. | +| 15 | Waypoint Mission | `true` when you are in the **WP Mission** flight mode. | #### WAYPOINTS @@ -216,7 +217,7 @@ The flight mode operands return `true` when the mode is active. These are modes | JUMP | 6 | | SET_HEAD | 7 | | LAND | 8 | - + ### Flags All flags are reseted on ARM and DISARM event. @@ -333,7 +334,7 @@ Steps: ## Common issues / questions about IPF -One common mistake involves setting RC channel values. To override (set) the +One common mistake involves setting RC channel values. To override (set) the value of a specific RC channel, choose "Override RC value", then for operand A choose *value* and enter the channel number. Choosing "get RC value" is a common mistake, which does something other than what you probably want. From 6f40120a24ec9d7192c40d59f64a91cefef166d0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 29 Jun 2024 21:16:26 +0200 Subject: [PATCH 059/212] Make gyro LULU independent from the gyro LPF --- src/main/build/debug.h | 1 + src/main/fc/settings.yaml | 8 +++++++- src/main/sensors/gyro.c | 33 ++++++++++++++++++++++++--------- src/main/sensors/gyro.h | 1 + 4 files changed, 33 insertions(+), 10 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index fea424b9005..ef32bf88734 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -76,6 +76,7 @@ typedef enum { DEBUG_POS_EST, DEBUG_ADAPTIVE_FILTER, DEBUG_HEADTRACKING, + DEBUG_LULU, DEBUG_COUNT } debugType_e; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ff42fb18fa7..1631d44b437 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -83,7 +83,7 @@ tables: values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE", - "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", "ADAPTIVE_FILTER", "HEADTRACKER" ] + "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", "ADAPTIVE_FILTER", "HEADTRACKER", "LULU" ] - name: aux_operator values: ["OR", "AND"] enum: modeActivationOperator_e @@ -226,10 +226,16 @@ groups: default_value: 250 field: gyro_anti_aliasing_lpf_hz max: 1000 + - name: gyro_lulu_enabled + description: "Enable/disable gyro LULU filter" + default_value: OFF + field: gyroLuluEnabled + type: bool - name: gyro_lulu_sample_count description: "Gyro lulu sample count, in number of samples." default_value: 3 field: gyroLuluSampleCount + min: 1 max: 15 - name: gyro_main_lpf_hz description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)" diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 780bada378d..9fa0a7c0e4d 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -135,7 +135,8 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .adaptiveFilterIntegratorThresholdLow = SETTING_GYRO_ADAPTIVE_FILTER_INTEGRATOR_THRESHOLD_LOW_DEFAULT, #endif .gyroFilterMode = SETTING_GYRO_FILTER_MODE_DEFAULT, - .gyroLuluSampleCount = SETTING_GYRO_LULU_SAMPLE_COUNT_DEFAULT + .gyroLuluSampleCount = SETTING_GYRO_LULU_SAMPLE_COUNT_DEFAULT, + .gyroLuluEnabled = SETTING_GYRO_LULU_ENABLED_DEFAULT ); STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware) @@ -248,9 +249,9 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t { *applyFn = nullFilterApply; if (cutoff > 0) { + *applyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); - *applyFn = (filterApplyFnPtr)pt1FilterApply; } } } @@ -260,14 +261,17 @@ static void gyroInitFilters(void) //First gyro LPF running at full gyro frequency 8kHz initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime()); - /* - luluFilterInit(&state[axis].lulu, cutoff); - *applyFn = (filterApplyFnPtr)luluFilterApply; - - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyroLuluSampleCount, getLooptime(), FILTER_LULU); - */ + if (gyroConfig()->gyroLuluEnabled && gyroConfig()->gyroLuluSampleCount > 0) { + gyroLuluApplyFn = (filterApplyFnPtr)luluFilterApply; - if(gyroConfig()->gyroFilterMode != GYRO_FILTER_MODE_OFF) { + for (int axis = 0; axis < 3; axis++) { + luluFilterInit(&gyroLuluState[axis].lulu, gyroConfig()->gyroLuluSampleCount); + } + } else { + gyroLuluApplyFn = nullFilterApply; + } + + if (gyroConfig()->gyroFilterMode != GYRO_FILTER_MODE_OFF) { initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime()); } else { gyroLpf2ApplyFn = nullFilterApply; @@ -467,6 +471,17 @@ void FAST_CODE NOINLINE gyroFilter(void) gyroADCf = rpmFilterGyroApply(axis, gyroADCf); #endif + // LULU gyro filter + DEBUG_SET(DEBUG_LULU, axis, gyroADCf); //Pre LULU debug + float preLulu = gyroADCf; + gyroADCf = gyroLuluApplyFn((filter_t *) &gyroLuluState[axis], gyroADCf); + DEBUG_SET(DEBUG_LULU, axis + 3, gyroADCf); //Post LULU debug + + if (axis == ROLL) { + DEBUG_SET(DEBUG_LULU, 6, gyroADCf - preLulu); //LULU delta debug + } + + // Gyro Main LPF gyroADCf = gyroLpf2ApplyFn((filter_t *) &gyroLpf2State[axis], gyroADCf); #ifdef USE_ADAPTIVE_FILTER diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index c6f60b45bbb..de78b2f81c2 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -105,6 +105,7 @@ typedef struct gyroConfig_s { uint8_t gyroFilterMode; uint8_t gyroLuluSampleCount; + bool gyroLuluEnabled; } gyroConfig_t; PG_DECLARE(gyroConfig_t, gyroConfig); From 449fb373f56680644b6f2dbb671810c2507d7592 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 29 Jun 2024 21:17:30 +0200 Subject: [PATCH 060/212] Docs update --- docs/Settings.md | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index 872c63bc423..a217a26a981 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1782,13 +1782,23 @@ Specifies the type of the software LPF of the gyro signals. --- +### gyro_lulu_enabled + +Enable/disable gyro LULU filter + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### gyro_lulu_sample_count Gyro lulu sample count, in number of samples. | Default | Min | Max | | --- | --- | --- | -| 3 | | 15 | +| 3 | 1 | 15 | --- From 0b237d1f06048fa03a24d1a9f4288f5a6b99cf8b Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 29 Jun 2024 23:50:31 +0100 Subject: [PATCH 061/212] nav course hold yaw stick improvement --- src/main/navigation/navigation.c | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 6eed742e804..5c0d7ec3431 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1339,6 +1339,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS } const bool mcRollStickHeadingAdjustmentActive = STATE(MULTIROTOR) && ABS(rcCommand[ROLL]) > rcControlsConfig()->pos_hold_deadband; + static bool adjustmentWasActive = false; // User demanding yaw -> yaw stick on FW, yaw or roll sticks on MR // We record the desired course and change the desired target in the meanwhile @@ -1353,9 +1354,19 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS if (timeDifference > 100) timeDifference = 0; // if adjustment was called long time ago, reset the time difference. float rateTarget = scaleRangef((float)headingAdjustCommand, -500.0f, 500.0f, -cruiseYawRate, cruiseYawRate); float centidegsPerIteration = rateTarget * MS2S(timeDifference); - posControl.cruise.course = wrap_36000(posControl.cruise.course - centidegsPerIteration); - DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.course)); + + if (ABS(wrap_18000(posControl.cruise.course - posControl.actualState.cog)) < fabsf(rateTarget)) { + posControl.cruise.course = wrap_36000(posControl.cruise.course - centidegsPerIteration); + } + posControl.cruise.lastCourseAdjustmentTime = currentTimeMs; + adjustmentWasActive = true; + + DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.course)); + } else if (STATE(AIRPLANE) && adjustmentWasActive) { + posControl.cruise.course = posControl.actualState.cog - DEGREES_TO_CENTIDEGREES(gyroRateDps(YAW)); + resetPositionController(); + adjustmentWasActive = false; } else if (currentTimeMs - posControl.cruise.lastCourseAdjustmentTime > 4000) { posControl.cruise.previousCourse = posControl.cruise.course; } From 1c427dab0114ce53e0d63aa0c1d203875e6ea52f Mon Sep 17 00:00:00 2001 From: p-i-engineer Date: Tue, 2 Jul 2024 06:32:47 -0700 Subject: [PATCH 062/212] Fixed position for formation flight / inav radar --- src/main/cms/cms_menu_osd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 4bde1291d5e..e99e0cc52f2 100644 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -237,6 +237,7 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("RADAR", OSD_RADAR), OSD_ELEMENT_ENTRY("MAP SCALE", OSD_MAP_SCALE), OSD_ELEMENT_ENTRY("MAP REFERENCE", OSD_MAP_REFERENCE), + OSD_ELEMENT_ENTRY("FORMATION FLIGHT", OSD_FORMATION_FLIGHT), #endif OSD_ELEMENT_ENTRY("EXPO", OSD_RC_EXPO), OSD_ELEMENT_ENTRY("YAW EXPO", OSD_RC_YAW_EXPO), From 6e3bf5198dcdc3f52887d0a596431fcecb7bf3fa Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 3 Jul 2024 20:52:16 +0200 Subject: [PATCH 063/212] Fix signal info struct size for NAV_SIG devices --- src/main/fc/cli.c | 35 +++++++++++++++----------- src/main/io/gps_ublox.c | 13 ++++++++-- src/main/io/gps_ublox.h | 39 ++++++++++++++++++++++++----- src/test/unit/gps_ublox_unittest.cc | 6 +++++ 4 files changed, 70 insertions(+), 23 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index fe54e175b27..7320ef060d6 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4370,15 +4370,15 @@ static const char* _ubloxGetSigId(uint8_t gnssId, uint8_t sigId) static const char *_ubloxGetQuality(uint8_t quality) { switch(quality) { - case 0: return "No signal"; - case 1: return "Searching signal..."; - case 2: return "Signal acquired"; - case 3: return "Signal detected but unusable"; - case 4: return "Code locked and time synch"; - case 5: - case 6: - case 7: - return "Code and carrier locked and time synch"; + case UBLOX_SIG_QUALITY_NOSIGNAL: return "No signal"; + case UBLOX_SIG_QUALITY_SEARCHING: return "Searching signal..."; + case UBLOX_SIG_QUALITY_ACQUIRED: return "Signal acquired"; + case UBLOX_SIG_QUALITY_UNUSABLE: return "Signal detected but unusable"; + case UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC: return "Code locked and time sync"; + case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC: + case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2: + case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3: + return "Code and carrier locked and time sync"; default: return "Unknown"; } } @@ -4407,12 +4407,17 @@ static void cliUbloxPrintSatelites(char *arg) //cliPrintLinef("Correlation: %i", sat->corrSource); //cliPrintLinef("Iono model: %i", sat->ionoModel); cliPrintLinef("signal flags: 0x%02X", sat->sigFlags); - if(sat->sigFlags & 0x01) { - cliPrintLine("signal: Healthy"); - } else if (sat->sigFlags & 0x02) { - cliPrintLine("signal: Unhealthy"); - } else { - cliPrintLine("signal: Unknown"); + switch(sat->sigFlags & UBLOX_SIG_HEALTH_MASK) { + case UBLOX_SIG_HEALTH_HEALTHY: + cliPrintLine("signal: Healthy"); + break; + case UBLOX_SIG_HEALTH_UNHEALTHY: + cliPrintLine("signal: Unhealthy"); + break; + case UBLOX_SIG_HEALTH_UNKNOWN: + default: + cliPrintLinef("signal: Unknown (0x%X)", sat->sigFlags & UBLOX_SIG_HEALTH_MASK); + break; } cliPrintLinefeed(); } diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 679bcf91e33..80bee7db441 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -720,23 +720,32 @@ static bool gpsParseFrameUBLOX(void) } break; - case MSG_SIG_INFO: + case MSG_NAV_SIG: if (_class == CLASS_NAV && _buffer.navsig.version == 0) { static int sigInfoCount = 0; DEBUG_SET(DEBUG_GPS, 2, sigInfoCount++); - DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); gpsState.flags.sig = 1; + // + //gpsSolDRV.numSat = _buffer.navSig.numSigs; // if good + int okSats = 0; if(_buffer.navsig.numSigs > 0) { for(int i=0; i < MIN(UBLOX_MAX_SIGNALS, _buffer.navsig.numSigs); ++i) { memcpy(&satelites[i], &_buffer.navsig.sig[i], sizeof(ubx_nav_sig_info)); + if ((_buffer.navsig.sig[i].sigFlags & UBLOX_SIG_HEALTH_MASK) == UBLOX_SIG_HEALTH_HEALTHY && + _buffer.navsig.sig[i].quality >= UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC) + { + okSats++; + } } for(int i = _buffer.navsig.numSigs; i < UBLOX_MAX_SIGNALS; ++i) { satelites[i].svId = 0xFF; // no used } } + //DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); + DEBUG_SET(DEBUG_GPS, 4, okSats); } break; case MSG_ACK_ACK: diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index c79c4654292..3a1c145b1b0 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -21,6 +21,7 @@ #include #include "common/time.h" +#include "build/debug.h" #ifdef __cplusplus extern "C" { @@ -28,8 +29,8 @@ extern "C" { #define GPS_CFG_CMD_TIMEOUT_MS 500 #define GPS_VERSION_RETRY_TIMES 3 -#define UBLOX_MAX_SIGNALS 32 -#define MAX_UBLOX_PAYLOAD_SIZE 640 // enough for anyone? // UBX-NAV-SIG info would be UBLOX_MAX_SIGNALS + 8 for (32 * 16) + 8 = 520 bytes +#define UBLOX_MAX_SIGNALS 64 +#define MAX_UBLOX_PAYLOAD_SIZE 1048 // enough for anyone? // UBX-NAV-SIG info would be UBLOX_MAX_SIGNALS * 16 + 8 for (64 * 16) + 8 = 1032 bytes #define UBLOX_BUFFER_SIZE MAX_UBLOX_PAYLOAD_SIZE #define UBLOX_SBAS_MESSAGE_LENGTH 16 #define GPS_CAPA_INTERVAL 5000 @@ -182,6 +183,33 @@ typedef struct { uint8_t reserved; } __attribute__((packed)) ubx_config_data_header_v1_t; +#define UBLOX_SIG_HEALTH_MASK (BIT(0) | BIT(1)) +#define UBLOX_SIG_PRSMOOTHED (BIT(2)) +#define UBLOX_SIG_PRUSED (BIT(3)) +#define UBLOX_SIG_CRUSED (BIT(4)) +#define UBLOX_SIG_DOUSED (BIT(5)) +#define UBLOX_SIG_PRCORRUSED (BIT(6)) +#define UBLOX_SIG_CRCORRUSED (BIT(7)) +#define UBLOX_SIG_DOCORRUSED (BIT(8)) +#define UBLOX_SIG_AUTHSTATUS (BIT(9)) + +typedef enum { + UBLOX_SIG_HEALTH_UNKNOWN = 0, + UBLOX_SIG_HEALTH_HEALTHY = 1, + UBLOX_SIG_HEALTH_UNHEALTHY = 2 +} ublox_nav_sig_health_e; + +typedef enum { + UBLOX_SIG_QUALITY_NOSIGNAL = 0, + UBLOX_SIG_QUALITY_SEARCHING = 1, + UBLOX_SIG_QUALITY_ACQUIRED = 2, + UBLOX_SIG_QUALITY_UNUSABLE = 3, + UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC = 4, + UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC = 5, + UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2 = 6, + UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3 = 7, +} ublox_nav_sig_quality; + typedef struct { uint8_t gnssId; // gnssid 0 = GPS, 1 = SBAS, 2 = GALILEO, 3 = BEIDOU, 4 = IMES, 5 = QZSS, 6 = GLONASS uint8_t svId; // space vehicle ID @@ -192,7 +220,7 @@ typedef struct { uint8_t quality; // 0 = no signal, 1 = search, 2 = acq, 3 = detected, 4 = code lock + time, 5,6,7 = code/carrier lock + time uint8_t corrSource; // Correction source: 0 = no correction, 1 = SBAS, 2 = BeiDou, 3 = RTCM2, 4 = RTCM3 OSR, 5 = RTCM3 SSR, 6 = QZSS SLAS, 7 = SPARTN uint8_t ionoModel; // 0 = no mode, 1 = Klobuchar GPS, 2 = SBAS, 3 = Klobuchar BeiDou, 8 = Iono derived from dual frequency observations - uint16_t sigFlags; // bit:0-1, 0 = unknown, 1 = healthy, 2 = unhealthy + uint16_t sigFlags; // bit:0-1 UBLOX_SIG_HEALTH_MASK // bit2: pseudorange smoothed, // bit3: pseudorange used, // bit4: carrioer range used; @@ -200,7 +228,7 @@ typedef struct { // bit6: pseudorange corrections used // bit7: carrier correction used // bit8: doper corrections used - uint8_t reserved; + uint8_t reserved[4]; } __attribute__((packed)) ubx_nav_sig_info; typedef struct { @@ -429,7 +457,6 @@ typedef enum { MSG_TIMEUTC = 0x21, MSG_SVINFO = 0x30, MSG_NAV_SAT = 0x35, - MSG_NAV_SIG = 0x35, MSG_CFG_PRT = 0x00, MSG_CFG_RATE = 0x08, MSG_CFG_SET_RATE = 0x01, @@ -437,7 +464,7 @@ typedef enum { MSG_CFG_SBAS = 0x16, MSG_CFG_GNSS = 0x3e, MSG_MON_GNSS = 0x28, - MSG_SIG_INFO = 0x43 + MSG_NAV_SIG = 0x43 } ubx_protocol_bytes_t; typedef enum { diff --git a/src/test/unit/gps_ublox_unittest.cc b/src/test/unit/gps_ublox_unittest.cc index bc20b340251..04de34e283b 100644 --- a/src/test/unit/gps_ublox_unittest.cc +++ b/src/test/unit/gps_ublox_unittest.cc @@ -87,4 +87,10 @@ TEST(GPSUbloxTest, TestUbloxCfgFillBytes) // osdFormatCentiNumber(buf, 12345, 1, 2, 3, 7); // std::cout << "'" << buf << "'" << std::endl; //EXPECT_FALSE(strcmp(buf, " 123.45")); +} + +TEST(GPSUbloxTest, navSigStructureSizes) { + EXPECT_TRUE(sizeof(ubx_nav_sig_info) == 16); + + EXPECT_TRUE(sizeof(ubx_nav_sig) == (8 + (16 * UBLOX_MAX_SIGNALS))); } \ No newline at end of file From cdcbd3f7ff7b27554612f0cc8c4ff94906e8ef2b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 3 Jul 2024 20:53:56 +0200 Subject: [PATCH 064/212] Remove some debugging info --- src/main/io/gps_ublox.c | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 80bee7db441..d674ea2d9de 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -724,28 +724,20 @@ static bool gpsParseFrameUBLOX(void) if (_class == CLASS_NAV && _buffer.navsig.version == 0) { static int sigInfoCount = 0; DEBUG_SET(DEBUG_GPS, 2, sigInfoCount++); + DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); gpsState.flags.sig = 1; - // - //gpsSolDRV.numSat = _buffer.navSig.numSigs; // if good - int okSats = 0; + if(_buffer.navsig.numSigs > 0) { for(int i=0; i < MIN(UBLOX_MAX_SIGNALS, _buffer.navsig.numSigs); ++i) { memcpy(&satelites[i], &_buffer.navsig.sig[i], sizeof(ubx_nav_sig_info)); - if ((_buffer.navsig.sig[i].sigFlags & UBLOX_SIG_HEALTH_MASK) == UBLOX_SIG_HEALTH_HEALTHY && - _buffer.navsig.sig[i].quality >= UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC) - { - okSats++; - } } for(int i = _buffer.navsig.numSigs; i < UBLOX_MAX_SIGNALS; ++i) { satelites[i].svId = 0xFF; // no used } } - //DEBUG_SET(DEBUG_GPS, 4, _buffer.navsig.numSigs); - DEBUG_SET(DEBUG_GPS, 4, okSats); } break; case MSG_ACK_ACK: From db459e5a4971bb78d2a99296197d9ffc7d9bed49 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 3 Jul 2024 22:18:09 +0200 Subject: [PATCH 065/212] NAV_SAT parsing --- src/main/io/gps_ublox.c | 12 ++---------- src/main/io/gps_ublox.h | 3 ++- src/main/io/gps_ublox_utils.c | 25 +++++++++++++++++++++++++ src/main/io/gps_ublox_utils.h | 2 ++ src/test/unit/gps_ublox_unittest.cc | 4 ++++ 5 files changed, 35 insertions(+), 11 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index d674ea2d9de..ae81326dd62 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -705,19 +705,11 @@ static bool gpsParseFrameUBLOX(void) } for(int i =0; i < MIN(_buffer.svinfo.numSvs, UBLOX_MAX_SIGNALS); ++i) { - satelites[i].svId = _buffer.svinfo.channel[i].svId; - satelites[i].gnssId = _buffer.svinfo.channel[i].gnssId; - satelites[i].sigId = 0; - satelites[i].cno = _buffer.svinfo.channel[i].cno; - satelites[i].cno = _buffer.svinfo.channel[i].flags; - satelites[i].quality = _buffer.svinfo.channel[i].flags & 0x3; - satelites[i].sigFlags = (_buffer.svinfo.channel[i].flags >> 4 & 0x3); // Healthy, not healthy - //satelites[i].cno = _buffer.svinfo.channel[i].quality; + ubloxNavSat2NavSig(&_buffer.svinfo.channel[i], &satelites[i]); } for(int i =_buffer.svinfo.numSvs; i < UBLOX_MAX_SIGNALS; ++i) { - satelites->svId = 0; + satelites->svId = 0xFF; } - } break; case MSG_NAV_SIG: diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 3a1c145b1b0..d1e9b148a65 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -21,6 +21,7 @@ #include #include "common/time.h" +#include "common/utils.h" #include "build/debug.h" #ifdef __cplusplus @@ -350,7 +351,7 @@ typedef struct { typedef struct { uint32_t itow; // GPS Millisecond time of week - uint8_t version; // Version = 0 + uint8_t version; // Version = 0-1 uint8_t numSvs; // (Space vehicle) Satelite count uint16_t reserved2; // Reserved ubx_nav_svinfo_channel channel[UBLOX_MAX_SIGNALS]; // UBLOX_MAX_SIGNALS satellites * 12 byte diff --git a/src/main/io/gps_ublox_utils.c b/src/main/io/gps_ublox_utils.c index 97c5bf5cd9a..bf0d0f264c0 100644 --- a/src/main/io/gps_ublox_utils.c +++ b/src/main/io/gps_ublox_utils.c @@ -17,6 +17,7 @@ #include +#include #include "gps_ublox_utils.h" @@ -60,3 +61,27 @@ int ubloxCfgFillBytes(ubx_config_data8_t *cfg, ubx_config_data8_payload_t *kvPai return count; } +void ubloxNavSat2NavSig(const ubx_nav_svinfo_channel *navSat, ubx_nav_sig_info *navSig) +{ + memset(navSig, 0, sizeof(ubx_nav_sig_info)); + navSig->svId = navSat->svId; + navSig->gnssId = navSat->gnssId; + navSig->cno = navSat->cno; + navSig->prRes = navSat->prRes; + navSig->quality = navSat->flags & (BIT(0)|BIT(1)|BIT(3)); + navSig->sigFlags = (navSat->flags >> 4) & (BIT(0)|BIT(1)); // Healthy, not healthy + // non-converted items: + //uint8_t sigId; // signal ID + //uint8_t freqId; // 0-13 slot +, 0-13, glonass only + //uint8_t corrSource; // Correction source: 0 = no correction, 1 = SBAS, 2 = BeiDou, 3 = RTCM2, 4 = RTCM3 OSR, 5 = RTCM3 SSR, 6 = QZSS SLAS, 7 = SPARTN + //uint8_t ionoModel; // 0 = no mode, 1 = Klobuchar GPS, 2 = SBAS, 3 = Klobuchar BeiDou, 8 = Iono derived from dual frequency observations + //uint16_t sigFlags; + // bit2: pseudorange smoothed, + // bit3: pseudorange used, + // bit4: carrioer range used; + // bit5: doppler used + // bit6: pseudorange corrections used + // bit7: carrier correction used + // bit8: doper corrections used + //uint8_t reserved[4]; +} \ No newline at end of file diff --git a/src/main/io/gps_ublox_utils.h b/src/main/io/gps_ublox_utils.h index e7ae0caac90..502bbaf31a6 100644 --- a/src/main/io/gps_ublox_utils.h +++ b/src/main/io/gps_ublox_utils.h @@ -29,6 +29,8 @@ int ubloxCfgFillBytes(ubx_config_data8_t *cfg, ubx_config_data8_payload_t *kvPai void ublox_update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b); +void ubloxNavSat2NavSig(const ubx_nav_svinfo_channel *navSat, ubx_nav_sig_info *navSig); + #ifdef __cplusplus } #endif diff --git a/src/test/unit/gps_ublox_unittest.cc b/src/test/unit/gps_ublox_unittest.cc index 04de34e283b..0628f8a1bdd 100644 --- a/src/test/unit/gps_ublox_unittest.cc +++ b/src/test/unit/gps_ublox_unittest.cc @@ -93,4 +93,8 @@ TEST(GPSUbloxTest, navSigStructureSizes) { EXPECT_TRUE(sizeof(ubx_nav_sig_info) == 16); EXPECT_TRUE(sizeof(ubx_nav_sig) == (8 + (16 * UBLOX_MAX_SIGNALS))); + + EXPECT_TRUE(sizeof(ubx_nav_svinfo_channel) == 12); + + EXPECT_TRUE(sizeof(ubx_nav_svinfo) == (8 + (12 * UBLOX_MAX_SIGNALS); } \ No newline at end of file From 78a6a2a858d62e0ff2cda3a3cb8183a9fbe6411b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 3 Jul 2024 22:24:39 +0200 Subject: [PATCH 066/212] Fix test --- src/test/unit/gps_ublox_unittest.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/test/unit/gps_ublox_unittest.cc b/src/test/unit/gps_ublox_unittest.cc index 0628f8a1bdd..ea5164b32a0 100644 --- a/src/test/unit/gps_ublox_unittest.cc +++ b/src/test/unit/gps_ublox_unittest.cc @@ -96,5 +96,5 @@ TEST(GPSUbloxTest, navSigStructureSizes) { EXPECT_TRUE(sizeof(ubx_nav_svinfo_channel) == 12); - EXPECT_TRUE(sizeof(ubx_nav_svinfo) == (8 + (12 * UBLOX_MAX_SIGNALS); + EXPECT_TRUE(sizeof(ubx_nav_svinfo) == (8 + (12 * UBLOX_MAX_SIGNALS))); } \ No newline at end of file From 7677abeb0c19bf50c9844f22ccb0a9b438a9bf0d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 3 Jul 2024 23:03:17 +0200 Subject: [PATCH 067/212] cleanup and static asserts --- src/main/io/gps_ublox.h | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index d1e9b148a65..287124581d4 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -21,6 +21,7 @@ #include #include "common/time.h" +#include "common/maths.h" #include "common/utils.h" #include "build/debug.h" @@ -30,12 +31,16 @@ extern "C" { #define GPS_CFG_CMD_TIMEOUT_MS 500 #define GPS_VERSION_RETRY_TIMES 3 +#ifndef UBLOX_MAX_SIGNALS #define UBLOX_MAX_SIGNALS 64 -#define MAX_UBLOX_PAYLOAD_SIZE 1048 // enough for anyone? // UBX-NAV-SIG info would be UBLOX_MAX_SIGNALS * 16 + 8 for (64 * 16) + 8 = 1032 bytes +#endif +#define MAX_UBLOX_PAYLOAD_SIZE ((UBLOX_MAX_SIGNALS * 16) + 8) // UBX-NAV-SIG info would be UBLOX_MAX_SIGNALS * 16 + 8 #define UBLOX_BUFFER_SIZE MAX_UBLOX_PAYLOAD_SIZE #define UBLOX_SBAS_MESSAGE_LENGTH 16 #define GPS_CAPA_INTERVAL 5000 +STATIC_ASSERT(MAX_UBLOX_PAYLOAD_SIZE >= 256, ubx_size_too_small); + #define UBX_DYNMODEL_PEDESTRIAN 3 #define UBX_DYNMODEL_AUTOMOVITE 4 #define UBX_DYNMODEL_AIR_1G 6 @@ -232,6 +237,8 @@ typedef struct { uint8_t reserved[4]; } __attribute__((packed)) ubx_nav_sig_info; +STATIC_ASSERT(sizeof(ubx_nav_sig_info) == 16, wrong_ubx_nav_sig_info_size); + typedef struct { uint32_t time; // GPS iToW uint8_t version; // We support version 0 @@ -349,6 +356,8 @@ typedef struct { uint32_t flags; // Bitmask } ubx_nav_svinfo_channel; +STATIC_ASSERT(sizeof(ubx_nav_svinfo_channel) == 12, wrong_ubx_nav_svinfo_channel_size); + typedef struct { uint32_t itow; // GPS Millisecond time of week uint8_t version; // Version = 0-1 From 341bb4f15f77c9c8001c68a8bd333531aac4ea36 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 4 Jul 2024 19:38:05 +0200 Subject: [PATCH 068/212] Add warning about old ublox versions --- src/main/fc/cli.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 7320ef060d6..c99e9111f5a 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3892,6 +3892,9 @@ static void cliStatus(char *cmdline) if (featureConfigured(FEATURE_GPS) && isGpsUblox()) { cliPrint("GPS: "); cliPrintf("HW Version: %s Proto: %d.%02d Baud: %d", getGpsHwVersion(), getGpsProtoMajorVersion(), getGpsProtoMinorVersion(), getGpsBaudrate()); + if(ubloxVersionLT(15, 0)) { + cliPrintf(" (UBLOX SW >= 15.0 required)"); + } cliPrintLinefeed(); cliPrintLinef(" SATS: %i", gpsSol.numSat); cliPrintLinef(" HDOP: %f", (double)(gpsSol.hdop / (float)HDOP_SCALE)); From 29ee096e336de7d20c5c35a516258f2866326fc1 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 4 Jul 2024 19:38:19 +0200 Subject: [PATCH 069/212] Make UBLOX functionally equal to UBLOX7 --- src/main/io/gps_ublox.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index ae81326dd62..175d283ddd4 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -704,7 +704,7 @@ static bool gpsParseFrameUBLOX(void) gpsSolDRV.numSat = _buffer.svinfo.numSvs; } - for(int i =0; i < MIN(_buffer.svinfo.numSvs, UBLOX_MAX_SIGNALS); ++i) { + for(int i = 0; i < MIN(_buffer.svinfo.numSvs, UBLOX_MAX_SIGNALS); ++i) { ubloxNavSat2NavSig(&_buffer.svinfo.channel[i], &satelites[i]); } for(int i =_buffer.svinfo.numSvs; i < UBLOX_MAX_SIGNALS; ++i) { @@ -978,7 +978,7 @@ STATIC_PROTOTHREAD(gpsConfigure) }// end message config ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_SHORT_TIMEOUT); - if ((gpsState.gpsConfig->provider == GPS_UBLOX7PLUS) && (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { + if ((gpsState.hwVersion >= UBX_HW_VERSION_UBLOX7)) { configureRATE(hz2rate(gpsState.gpsConfig->ubloxNavHz)); // default 10Hz } else { configureRATE(hz2rate(5)); // 5Hz @@ -1156,6 +1156,12 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread) void gpsRestartUBLOX(void) { + for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) + { + memset(&satelites[i], 0, sizeof(ubx_nav_sig_info)); + satelites[i].svId = 0xFF; + } + ptSemaphoreInit(semNewDataReady); ptRestart(ptGetHandle(gpsProtocolReceiverThread)); ptRestart(ptGetHandle(gpsProtocolStateThread)); From 017cb30bef73de8c8036e7cb9aa47aba08dbe629 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 4 Jul 2024 20:15:55 +0200 Subject: [PATCH 070/212] Small fixes. Add warning about ublox protocol version < 15.00 --- src/main/fc/cli.c | 2 +- src/main/io/gps_ublox.c | 20 ++++++++++++-------- src/main/io/gps_ublox_utils.c | 2 +- 3 files changed, 14 insertions(+), 10 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index c99e9111f5a..580859fec0c 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3893,7 +3893,7 @@ static void cliStatus(char *cmdline) cliPrint("GPS: "); cliPrintf("HW Version: %s Proto: %d.%02d Baud: %d", getGpsHwVersion(), getGpsProtoMajorVersion(), getGpsProtoMinorVersion(), getGpsBaudrate()); if(ubloxVersionLT(15, 0)) { - cliPrintf(" (UBLOX SW >= 15.0 required)"); + cliPrintf(" (UBLOX Proto >= 15.0 required)"); } cliPrintLinefeed(); cliPrintLinef(" SATS: %i", gpsSol.numSat); diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 175d283ddd4..fbe4a7f74ff 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -431,10 +431,10 @@ static void configureGNSS(void) { int blocksUsed = 0; send_buffer.message.header.msg_class = CLASS_CFG; - send_buffer.message.header.msg_id = MSG_CFG_GNSS; // message deprecated in protocol > 23.01, should use UBX-CFG-VALSET/UBX-CFG-VALGET + send_buffer.message.header.msg_id = MSG_CFG_GNSS; // message deprecated in protocol > 23.01, should use UBX-CFG-VALSET/UBX-CFG-VALGET send_buffer.message.payload.gnss.msgVer = 0; send_buffer.message.payload.gnss.numTrkChHw = 0; // read only, so unset - send_buffer.message.payload.gnss.numTrkChUse = 0xFF; // If set to 0xFF will use hardware max + send_buffer.message.payload.gnss.numTrkChUse = 0xFF; // If set to 0xFF will use hardware max /* SBAS, always generated */ blocksUsed += configureGNSS_SBAS(&send_buffer.message.payload.gnss.config[blocksUsed]); @@ -442,11 +442,11 @@ static void configureGNSS(void) /* Galileo */ blocksUsed += configureGNSS_GALILEO(&send_buffer.message.payload.gnss.config[blocksUsed]); - /* BeiDou */ - blocksUsed += configureGNSS_BEIDOU(&send_buffer.message.payload.gnss.config[blocksUsed]); + /* BeiDou */ + blocksUsed += configureGNSS_BEIDOU(&send_buffer.message.payload.gnss.config[blocksUsed]); - /* GLONASS */ - blocksUsed += configureGNSS_GLONASS(&send_buffer.message.payload.gnss.config[blocksUsed]); + /* GLONASS */ + blocksUsed += configureGNSS_GLONASS(&send_buffer.message.payload.gnss.config[blocksUsed]); send_buffer.message.payload.gnss.numConfigBlocks = blocksUsed; send_buffer.message.header.length = (sizeof(ubx_gnss_msg_t) + sizeof(ubx_gnss_element_t)* blocksUsed); @@ -708,6 +708,7 @@ static bool gpsParseFrameUBLOX(void) ubloxNavSat2NavSig(&_buffer.svinfo.channel[i], &satelites[i]); } for(int i =_buffer.svinfo.numSvs; i < UBLOX_MAX_SIGNALS; ++i) { + satelites->gnssId = 0xFF; satelites->svId = 0xFF; } } @@ -728,6 +729,7 @@ static bool gpsParseFrameUBLOX(void) for(int i = _buffer.navsig.numSigs; i < UBLOX_MAX_SIGNALS; ++i) { satelites[i].svId = 0xFF; // no used + satelites[i].gnssId = 0xFF; } } } @@ -1028,7 +1030,8 @@ STATIC_PROTOTHREAD(gpsConfigure) for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) { - satelites[i].svId = 0xFF; + satelites[i].svId = 0xFF; // no used + satelites[i].gnssId = 0xFF; } ptEnd(0); @@ -1160,6 +1163,7 @@ void gpsRestartUBLOX(void) { memset(&satelites[i], 0, sizeof(ubx_nav_sig_info)); satelites[i].svId = 0xFF; + satelites[i].gnssId = 0xFF; } ptSemaphoreInit(semNewDataReady); @@ -1191,7 +1195,7 @@ bool isGpsUblox(void) const ubx_nav_sig_info *gpsGetUbloxSatelite(uint8_t index) { - if(index < UBLOX_MAX_SIGNALS && satelites[index].svId != 0xFF) { + if(index < UBLOX_MAX_SIGNALS && satelites[index].svId != 0xFF && satelites[index].gnssId != 0xFF) { return &satelites[index]; } diff --git a/src/main/io/gps_ublox_utils.c b/src/main/io/gps_ublox_utils.c index bf0d0f264c0..a2adf1df18b 100644 --- a/src/main/io/gps_ublox_utils.c +++ b/src/main/io/gps_ublox_utils.c @@ -68,7 +68,7 @@ void ubloxNavSat2NavSig(const ubx_nav_svinfo_channel *navSat, ubx_nav_sig_info * navSig->gnssId = navSat->gnssId; navSig->cno = navSat->cno; navSig->prRes = navSat->prRes; - navSig->quality = navSat->flags & (BIT(0)|BIT(1)|BIT(3)); + navSig->quality = navSat->flags & (BIT(0)|BIT(1)|BIT(2)); navSig->sigFlags = (navSat->flags >> 4) & (BIT(0)|BIT(1)); // Healthy, not healthy // non-converted items: //uint8_t sigId; // signal ID From db54a7c56a9085a41cf9ae4cda1f3153cd93666c Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Fri, 5 Jul 2024 22:08:41 +0800 Subject: [PATCH 071/212] Add new targets: MicoAir405Mini, 405v2 and 743 --- src/main/target/MICOAIR405MINI/CMakeLists.txt | 1 + src/main/target/MICOAIR405MINI/config.c | 34 +++++ src/main/target/MICOAIR405MINI/target.c | 36 +++++ src/main/target/MICOAIR405MINI/target.h | 142 +++++++++++++++++ src/main/target/MICOAIR405V2/CMakeLists.txt | 1 + src/main/target/MICOAIR405V2/config.c | 34 +++++ src/main/target/MICOAIR405V2/target.c | 37 +++++ src/main/target/MICOAIR405V2/target.h | 143 ++++++++++++++++++ src/main/target/MICOAIR743/CMakeLists.txt | 1 + src/main/target/MICOAIR743/config.c | 34 +++++ src/main/target/MICOAIR743/target.c | 42 +++++ src/main/target/MICOAIR743/target.h | 141 +++++++++++++++++ 12 files changed, 646 insertions(+) create mode 100644 src/main/target/MICOAIR405MINI/CMakeLists.txt create mode 100644 src/main/target/MICOAIR405MINI/config.c create mode 100644 src/main/target/MICOAIR405MINI/target.c create mode 100644 src/main/target/MICOAIR405MINI/target.h create mode 100644 src/main/target/MICOAIR405V2/CMakeLists.txt create mode 100644 src/main/target/MICOAIR405V2/config.c create mode 100644 src/main/target/MICOAIR405V2/target.c create mode 100644 src/main/target/MICOAIR405V2/target.h create mode 100644 src/main/target/MICOAIR743/CMakeLists.txt create mode 100644 src/main/target/MICOAIR743/config.c create mode 100644 src/main/target/MICOAIR743/target.c create mode 100644 src/main/target/MICOAIR743/target.h diff --git a/src/main/target/MICOAIR405MINI/CMakeLists.txt b/src/main/target/MICOAIR405MINI/CMakeLists.txt new file mode 100644 index 00000000000..27ed5c945f4 --- /dev/null +++ b/src/main/target/MICOAIR405MINI/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(MICOAIR405MINI) \ No newline at end of file diff --git a/src/main/target/MICOAIR405MINI/config.c b/src/main/target/MICOAIR405MINI/config.c new file mode 100644 index 00000000000..00ee10a378d --- /dev/null +++ b/src/main/target/MICOAIR405MINI/config.c @@ -0,0 +1,34 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "config/config_master.h" +#include "config/feature.h" +#include "io/serial.h" +#include "fc/config.h" +#include "sensors/gyro.h" + + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; + serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_MSP_OSD; + serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[5].functionMask = FUNCTION_ESCSERIAL; +} diff --git a/src/main/target/MICOAIR405MINI/target.c b/src/main/target/MICOAIR405MINI/target.c new file mode 100644 index 00000000000..6903cb1cc49 --- /dev/null +++ b/src/main/target/MICOAIR405MINI/target.c @@ -0,0 +1,36 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MICOAIR405MINI/target.h b/src/main/target/MICOAIR405MINI/target.h new file mode 100644 index 00000000000..4b7e0b811da --- /dev/null +++ b/src/main/target/MICOAIR405MINI/target.h @@ -0,0 +1,142 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "MINI" + +#define USBD_PRODUCT_STRING "MICOAIR405MINI" + +// *************** LED ********************** +#define LED0 PC5 +#define LED1 PC4 +#define LED2 PA8 + +// *************** SPI: Gyro & ACC & BARO & OSD & SDCARD ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI2 +#define BMI270_CS_PIN PC14 + +#define USE_BARO +#define USE_BARO_DPS310 +#define DPS310_SPI_BUS BUS_SPI2 +#define DPS310_CS_PIN PC13 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN PB12 + +#define USE_BLACKBOX +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC9 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN NONE + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 +#define INVERTER_PIN_UART6_RX PC15 + +#define SERIAL_PORT_COUNT 7 //VCP, UART1, UART2, UART3, UART4, UART5, UART6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART6 +#define USE_UART_INVERTER + +// *************** I2C **************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define USE_MAG_ALL + +// *************** ENABLE OPTICAL FLOW & RANGEFINDER ***************************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define VBAT_SCALE_DEFAULT 2121 +#define CURRENT_METER_SCALE 402 + +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD | FEATURE_TELEMETRY) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 9 diff --git a/src/main/target/MICOAIR405V2/CMakeLists.txt b/src/main/target/MICOAIR405V2/CMakeLists.txt new file mode 100644 index 00000000000..1cd8dfbe968 --- /dev/null +++ b/src/main/target/MICOAIR405V2/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(MICOAIR405V2) diff --git a/src/main/target/MICOAIR405V2/config.c b/src/main/target/MICOAIR405V2/config.c new file mode 100644 index 00000000000..00ee10a378d --- /dev/null +++ b/src/main/target/MICOAIR405V2/config.c @@ -0,0 +1,34 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "config/config_master.h" +#include "config/feature.h" +#include "io/serial.h" +#include "fc/config.h" +#include "sensors/gyro.h" + + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; + serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_MSP_OSD; + serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[5].functionMask = FUNCTION_ESCSERIAL; +} diff --git a/src/main/target/MICOAIR405V2/target.c b/src/main/target/MICOAIR405V2/target.c new file mode 100644 index 00000000000..8c93f5394af --- /dev/null +++ b/src/main/target/MICOAIR405V2/target.c @@ -0,0 +1,37 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,7) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,2) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 -D(1,5) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1,6) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1,4) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 -D(1,5) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MICOAIR405V2/target.h b/src/main/target/MICOAIR405V2/target.h new file mode 100644 index 00000000000..c4a54f003b6 --- /dev/null +++ b/src/main/target/MICOAIR405V2/target.h @@ -0,0 +1,143 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "M405" + +#define USBD_PRODUCT_STRING "MICOAIR405V2" + +// *************** LED ********************** +#define LED0 PC5 +#define LED1 PC4 +#define LED2 PA8 + +// *************** SPI: Gyro & ACC & BARO & OSD & SDCARD ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_IMU_BMI088 +#define IMU_BMI088_ALIGN CW270_DEG +#define BMI088_SPI_BUS BUS_SPI2 +#define BMI088_GYRO_CS_PIN PC14 +#define BMI088_ACC_CS_PIN PC13 + +#define USE_BARO +#define USE_BARO_SPL06 +#define SPL06_SPI_BUS BUS_SPI2 +#define SPL06_CS_PIN PA4 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN PB12 + +#define USE_BLACKBOX +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC9 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN NONE + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 +#define INVERTER_PIN_UART6_RX PC15 + +#define SERIAL_PORT_COUNT 7 //VCP, UART1, UART2, UART3, UART4, UART5, UART6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART6 +#define USE_UART_INVERTER + +// *************** I2C **************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define USE_MAG_ALL + +// *************** ENABLE OPTICAL FLOW & RANGEFINDER ***************************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define VBAT_SCALE_DEFAULT 2121 +#define CURRENT_METER_SCALE 402 + +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD | FEATURE_TELEMETRY) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 10 diff --git a/src/main/target/MICOAIR743/CMakeLists.txt b/src/main/target/MICOAIR743/CMakeLists.txt new file mode 100644 index 00000000000..1d381638780 --- /dev/null +++ b/src/main/target/MICOAIR743/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(MICOAIR743) \ No newline at end of file diff --git a/src/main/target/MICOAIR743/config.c b/src/main/target/MICOAIR743/config.c new file mode 100644 index 00000000000..6f5be655693 --- /dev/null +++ b/src/main/target/MICOAIR743/config.c @@ -0,0 +1,34 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include "platform.h" +#include "config/config_master.h" +#include "config/feature.h" +#include "io/serial.h" +#include "fc/config.h" +#include "sensors/gyro.h" + + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; + serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_MSP_OSD; + serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_ESCSERIAL; +} diff --git a/src/main/target/MICOAIR743/target.c b/src/main/target/MICOAIR743/target.c new file mode 100644 index 00000000000..139fad35772 --- /dev/null +++ b/src/main/target/MICOAIR743/target.c @@ -0,0 +1,42 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MICOAIR743/target.h b/src/main/target/MICOAIR743/target.h new file mode 100644 index 00000000000..4ba27f3447e --- /dev/null +++ b/src/main/target/MICOAIR743/target.h @@ -0,0 +1,141 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "M743" + +#define USBD_PRODUCT_STRING "MICOAIR743" + +// *************** LED ********************** +#define LED0 PE5 +#define LED1 PE6 +#define LED2 PE4 + +// *************** SPI: Gyro & ACC & OSD ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_SCK_PIN PD3 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +#define USE_IMU_BMI088 +#define IMU_BMI088_ALIGN CW270_DEG +#define BMI088_SPI_BUS BUS_SPI2 +#define BMI088_GYRO_CS_PIN PD5 +#define BMI088_ACC_CS_PIN PD4 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN PB12 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PD9 +#define UART3_TX_PIN PD8 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 +#define INVERTER_PIN_UART6_RX PD0 + +#define USE_UART7 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_RX_PIN PE0 +#define UART8_TX_PIN PE1 + +#define SERIAL_PORT_COUNT 8 //VCP, UART1, UART2, UART3, UART4, UART6, UART7, UART8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART6 + +// *************** I2C: BARO & MAG **************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define USE_I2C_DEVICE_2 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define USE_BARO_DPS310 +#define BARO_I2C_BUS BUS_I2C2 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +// *************** ENABLE OPTICAL FLOW & RANGEFINDER ***************************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +// *************** SDIO SD BLACKBOX******************* +#define USE_SDCARD +#define USE_SDCARD_SDIO +#define SDCARD_SDIO_DEVICE SDIODEV_1 +#define SDCARD_SDIO_4BIT +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define VBAT_SCALE_DEFAULT 2121 +#define CURRENT_METER_SCALE 402 + +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_OSD | FEATURE_TELEMETRY) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 From 980784d941bfefe564cf28dec320fe0ca400b8a9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 5 Jul 2024 23:52:34 +0200 Subject: [PATCH 072/212] Fix GPS dynamic model setup for M10 GPS units --- src/main/io/gps_ublox.c | 74 ++++++++++++++++++++++++++++++----------- src/main/io/gps_ublox.h | 10 ++++++ 2 files changed, 64 insertions(+), 20 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index fbe4a7f74ff..623f2f5ae2e 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -865,25 +865,57 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // Set dynamic model - switch (gpsState.gpsConfig->dynModel) { - case GPS_DYNMODEL_PEDESTRIAN: - configureNAV5(UBX_DYNMODEL_PEDESTRIAN, UBX_FIXMODE_AUTO); - break; - case GPS_DYNMODEL_AUTOMOTIVE: - configureNAV5(UBX_DYNMODEL_AUTOMOVITE, UBX_FIXMODE_AUTO); - break; - case GPS_DYNMODEL_AIR_1G: - configureNAV5(UBX_DYNMODEL_AIR_1G, UBX_FIXMODE_AUTO); - break; - case GPS_DYNMODEL_AIR_2G: // Default to this - default: - configureNAV5(UBX_DYNMODEL_AIR_2G, UBX_FIXMODE_AUTO); - break; - case GPS_DYNMODEL_AIR_4G: - configureNAV5(UBX_DYNMODEL_AIR_4G, UBX_FIXMODE_AUTO); - break; + if (ubloxVersionGTE(23, 1)) { + ubx_config_data8_payload_t dynmodelCfg[] = { + {UBLOX_CFG_NAVPSG_DYNMODEL, UBX_DYNMODEL_AIR_2G}, + {UBLOX_CFG_NAVPSG_FIXMODE, UBX_FIXMODE_AUTO} + }; + + switch (gpsState.gpsConfig->dynModel) { + case GPS_DYNMODEL_PEDESTRIAN: + dynmodelCfg[0].value = UBX_DYNMODEL_PEDESTRIAN; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + case GPS_DYNMODEL_AUTOMOTIVE: + dynmodelCfg[0].value = UBX_DYNMODEL_AUTOMOVITE; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + case GPS_DYNMODEL_AIR_1G: + dynmodelCfg[0].value = UBX_DYNMODEL_AIR_1G; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + case GPS_DYNMODEL_AIR_2G: // Default to this + default: + dynmodelCfg[0].value = UBX_DYNMODEL_AIR_2G; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + case GPS_DYNMODEL_AIR_4G: + dynmodelCfg[0].value = UBX_DYNMODEL_AIR_4G; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + } + ptWait(_ack_state == UBX_ACK_GOT_ACK); + } else { + switch (gpsState.gpsConfig->dynModel) { + case GPS_DYNMODEL_PEDESTRIAN: + configureNAV5(UBX_DYNMODEL_PEDESTRIAN, UBX_FIXMODE_AUTO); + break; + case GPS_DYNMODEL_AUTOMOTIVE: + configureNAV5(UBX_DYNMODEL_AUTOMOVITE, UBX_FIXMODE_AUTO); + break; + case GPS_DYNMODEL_AIR_1G: + configureNAV5(UBX_DYNMODEL_AIR_1G, UBX_FIXMODE_AUTO); + break; + case GPS_DYNMODEL_AIR_2G: // Default to this + default: + configureNAV5(UBX_DYNMODEL_AIR_2G, UBX_FIXMODE_AUTO); + break; + case GPS_DYNMODEL_AIR_4G: + configureNAV5(UBX_DYNMODEL_AIR_4G, UBX_FIXMODE_AUTO); + break; + } + ptWait(_ack_state == UBX_ACK_GOT_ACK); } - ptWait(_ack_state == UBX_ACK_GOT_ACK); gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // Disable NMEA messages @@ -960,6 +992,7 @@ STATIC_PROTOTHREAD(gpsConfigure) configureMSG(MSG_CLASS_UBX, MSG_NAV_SAT, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK); } else { // Really old stuff, consider upgrading :), ols setting API, no PVT or NAV_SAT or NAV_SIG + // TODO: remove in INAV 9.0.0 configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 1); ptWait(_ack_state == UBX_ACK_GOT_ACK); @@ -1006,7 +1039,7 @@ STATIC_PROTOTHREAD(gpsConfigure) ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); // Configure GNSS for M8N and later - if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX8) { + if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX8) { // TODO: This check can be remove in INAV 9.0.0 gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); bool use_VALSET = 0; if (ubloxVersionGTE(23,1)) { @@ -1030,7 +1063,8 @@ STATIC_PROTOTHREAD(gpsConfigure) for(int i = 0; i < UBLOX_MAX_SIGNALS; ++i) { - satelites[i].svId = 0xFF; // no used + // Mark satelites as unused + satelites[i].svId = 0xFF; satelites[i].gnssId = 0xFF; } diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 287124581d4..89142b51a9b 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -41,11 +41,18 @@ extern "C" { STATIC_ASSERT(MAX_UBLOX_PAYLOAD_SIZE >= 256, ubx_size_too_small); +#define UBX_DYNMODEL_PORTABLE 0 +#define UBX_DYNMODEL_STATIONARY 2 #define UBX_DYNMODEL_PEDESTRIAN 3 #define UBX_DYNMODEL_AUTOMOVITE 4 +#define UBX_DYNMODEL_SEA 5 #define UBX_DYNMODEL_AIR_1G 6 #define UBX_DYNMODEL_AIR_2G 7 #define UBX_DYNMODEL_AIR_4G 8 +#define UBX_DYNMODEL_WRIST 9 +#define UBX_DYNMODEL_BIKE 10 +#define UBX_DYNMODEL_MOWER 11 +#define UBX_DYNMODEL_ESCOOTER 12 #define UBX_FIXMODE_2D_ONLY 1 #define UBX_FIXMODE_3D_ONLY 2 @@ -75,6 +82,9 @@ STATIC_ASSERT(MAX_UBLOX_PAYLOAD_SIZE >= 256, ubx_size_too_small); #define UBLOX_CFG_MSGOUT_NMEA_ID_GSA_UART1 0x209100c0 // U1 #define UBLOX_CFG_MSGOUT_NMEA_ID_RMC_UART1 0x209100ac // U1 #define UBLOX_CFG_MSGOUT_NMEA_ID_VTG_UART1 0x209100b1 // U1 +#define UBLOX_CFG_NAVSPG_FIXMODE 0x20110011 // E1 +#define UBLOX_CFG_NAVSPG_DYNMODEL 0x20110021 // E1 + #define UBLOX_CFG_SIGNAL_SBAS_ENA 0x10310020 // U1 #define UBLOX_CFG_SIGNAL_SBAS_L1CA_ENA 0x10310005 // U1 From 938f392ccc59795ef95a52114d87fecbcc6edb0f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 6 Jul 2024 00:05:10 +0200 Subject: [PATCH 073/212] fix typo --- src/main/io/gps_ublox.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 623f2f5ae2e..40ea17fe2cb 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -867,8 +867,8 @@ STATIC_PROTOTHREAD(gpsConfigure) // Set dynamic model if (ubloxVersionGTE(23, 1)) { ubx_config_data8_payload_t dynmodelCfg[] = { - {UBLOX_CFG_NAVPSG_DYNMODEL, UBX_DYNMODEL_AIR_2G}, - {UBLOX_CFG_NAVPSG_FIXMODE, UBX_FIXMODE_AUTO} + {UBLOX_CFG_NAVSPG_DYNMODEL, UBX_DYNMODEL_AIR_2G}, + {UBLOX_CFG_NAVSPG_FIXMODE, UBX_FIXMODE_AUTO} }; switch (gpsState.gpsConfig->dynModel) { From 798f1ac2544010804442312dabda0ae2eb9220dc Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 6 Jul 2024 18:18:20 -0500 Subject: [PATCH 074/212] mixer.h: PLATFORM_OTHER isn't valid, remove --- src/main/flight/mixer.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 8af82173069..12688bd2c09 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -40,8 +40,7 @@ typedef enum { PLATFORM_HELICOPTER = 2, PLATFORM_TRICOPTER = 3, PLATFORM_ROVER = 4, - PLATFORM_BOAT = 5, - PLATFORM_OTHER = 6 + PLATFORM_BOAT = 5 } flyingPlatformType_e; @@ -132,4 +131,4 @@ void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); bool areMotorsRunning(void); -uint16_t getMaxThrottle(void); \ No newline at end of file +uint16_t getMaxThrottle(void); From 463fe1a877f58d4291201360179274029f998fe3 Mon Sep 17 00:00:00 2001 From: Roberto Date: Sun, 7 Jul 2024 14:43:36 +0200 Subject: [PATCH 075/212] Fix typo Rx.md --- docs/Rx.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Rx.md b/docs/Rx.md index ec34f4e6f9e..c52fe151571 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -205,7 +205,7 @@ Note: ## SIM (SITL) Joystick -Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL). +Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL.md). ## Configuration From 32203d81edff2db9847c9952e7a9e137672dc950 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 15:21:39 +0200 Subject: [PATCH 076/212] Set gps rate with current api. The old message probably works on M10 by accident, as it is not even mentioned in the manual anymore. --- src/main/io/gps_ublox.c | 52 ++++++++++++++++++++++++++++++----- src/main/io/gps_ublox.h | 22 +++++++++++++++ src/main/io/gps_ublox_utils.c | 31 ++++++++++++++++++++- src/main/io/gps_ublox_utils.h | 1 + 4 files changed, 98 insertions(+), 8 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 40ea17fe2cb..30e653782c2 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -288,6 +288,19 @@ static void ubloxSendSetCfgBytes(ubx_config_data8_payload_t *kvPairs, uint8_t co _ack_state = UBX_ACK_WAITING; } +// M10 ublox protocol info: +// https://content.u-blox.com/sites/default/files/u-blox-M10-SPG-5.10_InterfaceDescription_UBX-21035062.pdf +static void ubloxSendSetCfgU2(ubx_config_data16_payload_t *kvPairs, uint8_t count) +{ + ubx_config_data16_t cfg = {}; + + ubloxCfgFillU2(&cfg, kvPairs, count); + + serialWriteBuf(gpsState.gpsPort, (uint8_t *)&cfg, cfg.header.length+8); + _ack_waiting_msg = cfg.header.msg_id; + _ack_state = UBX_ACK_WAITING; +} + // Info on protocol used by M8-M9, check UBX-CFG-GNSS for gnss configuration // https://content.u-blox.com/sites/default/files/products/documents/u-blox8-M8_ReceiverDescrProtSpec_UBX-13003221.pdf // https://content.u-blox.com/sites/default/files/documents/u-blox-F9-HPG-1.32_InterfaceDescription_UBX-22008968.pdf @@ -482,13 +495,38 @@ static void configureMSG(uint8_t msg_class, uint8_t id, uint8_t rate) */ static void configureRATE(uint16_t measRate) { - send_buffer.message.header.msg_class = CLASS_CFG; - send_buffer.message.header.msg_id = MSG_CFG_RATE; - send_buffer.message.header.length = 6; - send_buffer.message.payload.rate.meas=measRate; - send_buffer.message.payload.rate.nav=1; - send_buffer.message.payload.rate.time=1; - sendConfigMessageUBLOX(); + if(ubloxVersionLT(24, 0)) { + measRate = MAX(50, measRate); + } else { + measRate = MAX(25, measRate); + } + + if (ubloxVersionLT(23, 1)) { + send_buffer.message.header.msg_class = CLASS_CFG; + send_buffer.message.header.msg_id = MSG_CFG_RATE; + send_buffer.message.header.length = 6; + send_buffer.message.payload.rate.meas = measRate; + send_buffer.message.payload.rate.nav = 1; + send_buffer.message.payload.rate.time = 1; + sendConfigMessageUBLOX(); + } else { // M10+ + // 1 is already default, for TIMEREF. + // The wait the configuration happens, + // it is tricky to wait for multiple commands. + // SendSetCfg could be refactored to support U1, U2, U3 and U4 messages + // at the same time. For now, leave it out. + // + //ubx_config_data8_payload_t rateValues[] = { + // {UBLOX_CFG_RATE_TIMEREF, 1}, // 0 + //}; + //ubloxSendSetCfgBytes(rateValues, 1); + + ubx_config_data16_payload_t rate16Values[] = { + {UBLOX_CFG_RATE_MEAS, measRate}, + {UBLOX_CFG_RATE_NAV, 1} + }; + ubloxSendSetCfgU2(rate16Values, 2); + } } /* diff --git a/src/main/io/gps_ublox.h b/src/main/io/gps_ublox.h index 89142b51a9b..ab0ab930275 100644 --- a/src/main/io/gps_ublox.h +++ b/src/main/io/gps_ublox.h @@ -84,6 +84,10 @@ STATIC_ASSERT(MAX_UBLOX_PAYLOAD_SIZE >= 256, ubx_size_too_small); #define UBLOX_CFG_MSGOUT_NMEA_ID_VTG_UART1 0x209100b1 // U1 #define UBLOX_CFG_NAVSPG_FIXMODE 0x20110011 // E1 #define UBLOX_CFG_NAVSPG_DYNMODEL 0x20110021 // E1 +#define UBLOX_CFG_RATE_MEAS 0x30210001 // U2 +#define UBLOX_CFG_RATE_NAV 0x30210002 // U2 +#define UBLOX_CFG_RATE_TIMEREF 0x30210002 // E1 + #define UBLOX_CFG_SIGNAL_SBAS_ENA 0x10310020 // U1 @@ -282,6 +286,13 @@ typedef struct { uint8_t value; } __attribute__((packed)) ubx_config_data8_payload_t; +typedef struct { + uint32_t key; + uint16_t value; +} __attribute__((packed)) ubx_config_data16_payload_t; + + + #define MAX_CONFIG_SET_VAL_VALUES 32 @@ -294,6 +305,17 @@ typedef struct { } data; } __attribute__((packed)) ubx_config_data8_t; +typedef struct { + ubx_header header; + ubx_config_data_header_v1_t configHeader; + union { + ubx_config_data16_payload_t payload[0]; + uint8_t buffer[(MAX_CONFIG_SET_VAL_VALUES * sizeof(ubx_config_data16_payload_t)) + 2]; // 12 key/value pairs + 2 checksum bytes + } data; +} __attribute__((packed)) ubx_config_data16_t; + + + typedef struct { ubx_header header; ubx_payload payload; diff --git a/src/main/io/gps_ublox_utils.c b/src/main/io/gps_ublox_utils.c index a2adf1df18b..b2daef21bfa 100644 --- a/src/main/io/gps_ublox_utils.c +++ b/src/main/io/gps_ublox_utils.c @@ -48,7 +48,36 @@ int ubloxCfgFillBytes(ubx_config_data8_t *cfg, ubx_config_data8_payload_t *kvPai for (int i = 0; i < count; ++i) { - cfg->data.payload[i].key = kvPairs[i].key; //htonl(kvPairs[i].key); + cfg->data.payload[i].key = kvPairs[i].key; + cfg->data.payload[i].value = kvPairs[i].value; + } + + uint8_t *buf = (uint8_t *)cfg; + uint8_t ck_a, ck_b; + ublox_update_checksum(buf + 2, cfg->header.length + 4, &ck_a, &ck_b); + buf[cfg->header.length + 6] = ck_a; + buf[cfg->header.length + 7] = ck_b; + + return count; +} + +int ubloxCfgFillU2(ubx_config_data16_t *cfg, ubx_config_data16_payload_t *kvPairs, uint8_t count) +{ + if (count > MAX_CONFIG_SET_VAL_VALUES) + count = MAX_CONFIG_SET_VAL_VALUES; + + cfg->header.preamble1 = 0xb5; + cfg->header.preamble2 = 0x62; + cfg->header.msg_class = 0x06; + cfg->header.msg_id = 0x16A; + cfg->header.length = sizeof(ubx_config_data_header_v1_t) + ((sizeof(ubx_config_data16_payload_t) * count)); + cfg->configHeader.layers = 0x1; + cfg->configHeader.transaction = 0; + cfg->configHeader.reserved = 0; + cfg->configHeader.version = 1; + + for (int i = 0; i < count; ++i) { + cfg->data.payload[i].key = kvPairs[i].key; cfg->data.payload[i].value = kvPairs[i].value; } diff --git a/src/main/io/gps_ublox_utils.h b/src/main/io/gps_ublox_utils.h index 502bbaf31a6..996cbe2a68c 100644 --- a/src/main/io/gps_ublox_utils.h +++ b/src/main/io/gps_ublox_utils.h @@ -26,6 +26,7 @@ extern "C" { #endif int ubloxCfgFillBytes(ubx_config_data8_t *cfg, ubx_config_data8_payload_t *kvPairs, uint8_t count); +int ubloxCfgFillU2(ubx_config_data16_t *cfg, ubx_config_data16_payload_t *kvPairs, uint8_t count); void ublox_update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b); From 64d8293f3677ac20b76e1bb2b04600d8c80282eb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 15:29:14 +0200 Subject: [PATCH 077/212] Fix msg_id --- src/main/io/gps_ublox_utils.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox_utils.c b/src/main/io/gps_ublox_utils.c index b2daef21bfa..c9c1682a5f7 100644 --- a/src/main/io/gps_ublox_utils.c +++ b/src/main/io/gps_ublox_utils.c @@ -69,7 +69,7 @@ int ubloxCfgFillU2(ubx_config_data16_t *cfg, ubx_config_data16_payload_t *kvPair cfg->header.preamble1 = 0xb5; cfg->header.preamble2 = 0x62; cfg->header.msg_class = 0x06; - cfg->header.msg_id = 0x16A; + cfg->header.msg_id = 0x8A; cfg->header.length = sizeof(ubx_config_data_header_v1_t) + ((sizeof(ubx_config_data16_payload_t) * count)); cfg->configHeader.layers = 0x1; cfg->configHeader.transaction = 0; From 90bba03870fcfecadec6de5b010214f6f0faa7b6 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 15:38:21 +0200 Subject: [PATCH 078/212] less than vs less than or equal on CFG-RATE check --- src/main/io/gps_ublox.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 30e653782c2..8f7a96098dd 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -501,7 +501,7 @@ static void configureRATE(uint16_t measRate) measRate = MAX(25, measRate); } - if (ubloxVersionLT(23, 1)) { + if (ubloxVersionLTE(23, 1)) { send_buffer.message.header.msg_class = CLASS_CFG; send_buffer.message.header.msg_id = MSG_CFG_RATE; send_buffer.message.header.length = 6; From 1c0fb3feca38a7896fa9c52fb8db17d5e69c664c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 15:50:21 +0200 Subject: [PATCH 079/212] Update comments --- src/main/io/gps_ublox.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 8f7a96098dd..9cc4aa76954 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1005,7 +1005,7 @@ STATIC_PROTOTHREAD(gpsConfigure) ubloxSendSetCfgBytes(rateValues, 7); ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS); - } else if(ubloxVersionGTE(15,0)) { // M8 and potentially M7, PVT, NAV_SAT, old setting API + } else if(ubloxVersionGTE(15,0)) { // M8, PVT, NAV_SAT, old setting API configureMSG(MSG_CLASS_UBX, MSG_POSLLH, 0); ptWait(_ack_state == UBX_ACK_GOT_ACK); From 6e1a76148d248c2439fddaa180e760f70c2f01bb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 09:50:44 -0400 Subject: [PATCH 080/212] Add UBLOX PSA Add PSA about M7, M6 and older GPS units. From INAV 9.0.0, you will need a UBLOX unit with Protocol version > 15.0 --- readme.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/readme.md b/readme.md index 53710d519aa..ac5445aff5f 100644 --- a/readme.md +++ b/readme.md @@ -10,6 +10,15 @@ > The filtering settings for the ICM426xx has changed to match what is used by Ardupilot and Betaflight in INAV 7.1. When upgrading from older versions you may need to recalibrate the Accelerometer and if you are not using INAV's default tune you may also want to check if the tune is still good. +# M7, M6 and older UBLOX GPS units PSA + +> INAV 8.0 will mark those GPS as deprecated and INAV 9.0.0 will require UBLOX units with Protocol version 15.00 or newer. This means that you need a GPS unit based on UBLOX M8 or newer. + +> If you want to check the protocol version of your unit, it is displayed in INAV's 7.0.0+ status cli command. + +> M8, M9 and M10 GPS are the most common units in use today, are readly available and have similar capabilities. +>Mantaining and testing GPS changes across this many UBLOX versions is a challenge and takes a lot of time. Removing the support for older devices will simplify code. + ![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png) # PosHold, Navigation and RTH without compass PSA From 575416547f11edea055e794cf054b31579206451 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 10:46:23 -0400 Subject: [PATCH 081/212] Update readme.md --- readme.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/readme.md b/readme.md index ac5445aff5f..1c313de3569 100644 --- a/readme.md +++ b/readme.md @@ -15,6 +15,9 @@ > INAV 8.0 will mark those GPS as deprecated and INAV 9.0.0 will require UBLOX units with Protocol version 15.00 or newer. This means that you need a GPS unit based on UBLOX M8 or newer. > If you want to check the protocol version of your unit, it is displayed in INAV's 7.0.0+ status cli command. +> INAV 8.0.0 will warn you if your GPS is too old. +> ```GPS: HW Version: Unknown Proto: 0.00 Baud: 115200 (UBLOX Proto >= 15.0 required)``` + > M8, M9 and M10 GPS are the most common units in use today, are readly available and have similar capabilities. >Mantaining and testing GPS changes across this many UBLOX versions is a challenge and takes a lot of time. Removing the support for older devices will simplify code. From 2bab471451a7bb8ee20f351b36cd0511b052fc13 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 7 Jul 2024 17:18:37 +0200 Subject: [PATCH 082/212] LTE/GT for 23.1 protocol --- src/main/io/gps_ublox.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 9cc4aa76954..9b5a65647cb 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -903,7 +903,7 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // Set dynamic model - if (ubloxVersionGTE(23, 1)) { + if (ubloxVersionGT(23, 1)) { ubx_config_data8_payload_t dynmodelCfg[] = { {UBLOX_CFG_NAVSPG_DYNMODEL, UBX_DYNMODEL_AIR_2G}, {UBLOX_CFG_NAVSPG_FIXMODE, UBX_FIXMODE_AUTO} @@ -957,7 +957,7 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // Disable NMEA messages - if (ubloxVersionGTE(23, 1)) { + if (ubloxVersionGT(23, 1)) { ubx_config_data8_payload_t nmeaValues[] = { { UBLOX_CFG_MSGOUT_NMEA_ID_GGA_UART1, 0 }, { UBLOX_CFG_MSGOUT_NMEA_ID_GLL_UART1, 0 }, @@ -992,7 +992,7 @@ STATIC_PROTOTHREAD(gpsConfigure) gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); // M9N & M10 does not support some of the UBX 6/7/8 messages, so we have to configure it using special sequence - if (ubloxVersionGTE(23, 1)) { // M9+, new setting API, PVT and NAV_SIG + if (ubloxVersionGT(23, 1)) { // M9+, new setting API, PVT and NAV_SIG ubx_config_data8_payload_t rateValues[] = { {UBLOX_CFG_MSGOUT_NAV_POSLLH_UART1, 0}, // 0 {UBLOX_CFG_MSGOUT_NAV_STATUS_UART1, 0}, // 1 @@ -1080,7 +1080,7 @@ STATIC_PROTOTHREAD(gpsConfigure) if (gpsState.hwVersion >= UBX_HW_VERSION_UBLOX8) { // TODO: This check can be remove in INAV 9.0.0 gpsSetProtocolTimeout(GPS_SHORT_TIMEOUT); bool use_VALSET = 0; - if (ubloxVersionGTE(23,1)) { + if (ubloxVersionGT(23,1)) { use_VALSET = 1; } From c02444e0480ec4107e80ad1f00964c89f9d2e9cf Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 7 Jul 2024 11:50:20 -0500 Subject: [PATCH 083/212] IFLIGHT_BLITZ_ATF435 MAX_PWM_OUTPUT_PORTS should 8 --- src/main/target/IFLIGHT_BLITZ_ATF435/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/IFLIGHT_BLITZ_ATF435/target.h b/src/main/target/IFLIGHT_BLITZ_ATF435/target.h index b29112d5256..19f1483dfeb 100644 --- a/src/main/target/IFLIGHT_BLITZ_ATF435/target.h +++ b/src/main/target/IFLIGHT_BLITZ_ATF435/target.h @@ -159,6 +159,6 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE BIT(2) -#define MAX_PWM_OUTPUT_PORTS 4 +#define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT #define USE_ESC_SENSOR From 9d5b40bcb512710cd90e03c3e02fda670d53031c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 8 Jul 2024 22:49:38 +0200 Subject: [PATCH 084/212] Add SEA and MOWER dynamic models. Potentially better models for hovers --- src/main/fc/settings.yaml | 4 ++-- src/main/io/gps.h | 2 ++ src/main/io/gps_ublox.c | 14 ++++++++++++++ 3 files changed, 18 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index d8dd7d6fbee..278be344339 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -48,7 +48,7 @@ tables: values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"] enum: sbasMode_e - name: gps_dyn_model - values: ["PEDESTRIAN","AUTOMOTIVE", "AIR_1G", "AIR_2G", "AIR_4G"] + values: ["PEDESTRIAN","AUTOMOTIVE", "AIR_1G", "AIR_2G", "AIR_4G", "SEA", "MOWER"] enum: gpsDynModel_e - name: reset_type values: ["NEVER", "FIRST_ARM", "EACH_ARM"] @@ -4307,4 +4307,4 @@ groups: default_value: 1 field: roll_ratio min: 0 - max: 5 \ No newline at end of file + max: 5 diff --git a/src/main/io/gps.h b/src/main/io/gps.h index cd8f909d344..7b78fe5e799 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -80,6 +80,8 @@ typedef enum { GPS_DYNMODEL_AIR_1G, GPS_DYNMODEL_AIR_2G, GPS_DYNMODEL_AIR_4G, + GPS_DYNMODEL_SEA, + GPS_DYNMODEL_MOWER, } gpsDynModel_e; typedef enum { diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 9b5a65647cb..725ecfd862d 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -931,6 +931,14 @@ STATIC_PROTOTHREAD(gpsConfigure) dynmodelCfg[0].value = UBX_DYNMODEL_AIR_4G; ubloxSendSetCfgBytes(dynmodelCfg, 2); break; + case GPS_DYNMODEL_SEA: + dynmodelCfg[0].value = UBX_DYNMODEL_SEA; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; + case GPS_DYNMODEL_MOWER: + dynmodelCfg[0].value = UBX_DYNMODEL_MOWER; + ubloxSendSetCfgBytes(dynmodelCfg, 2); + break; } ptWait(_ack_state == UBX_ACK_GOT_ACK); } else { @@ -951,6 +959,12 @@ STATIC_PROTOTHREAD(gpsConfigure) case GPS_DYNMODEL_AIR_4G: configureNAV5(UBX_DYNMODEL_AIR_4G, UBX_FIXMODE_AUTO); break; + case GPS_DYNMODEL_SEA: + configureNAV5(UBX_DYNMODEL_SEA, UBX_FIXMODE_AUTO); + break; + case GPS_DYNMODEL_MOWER: + configureNAV5(UBX_DYNMODEL_MOWER, UBX_FIXMODE_AUTO); + break; } ptWait(_ack_state == UBX_ACK_GOT_ACK); } From 3eafbe6acbaed83a13dcbb1df94ff78a0a5f544d Mon Sep 17 00:00:00 2001 From: jamming Date: Tue, 9 Jul 2024 10:14:59 +0800 Subject: [PATCH 085/212] Fix DMA conflict of TIM1 and ADC1 --- src/main/target/KAKUTEF4WING/target.c | 4 ++-- src/main/target/KAKUTEF4WING/target.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/KAKUTEF4WING/target.c b/src/main/target/KAKUTEF4WING/target.c index 8c2240a9c3b..f6956dae169 100755 --- a/src/main/target/KAKUTEF4WING/target.c +++ b/src/main/target/KAKUTEF4WING/target.c @@ -30,10 +30,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1_OUT - DMA2_ST1_CH6 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA2_ST6_CH0 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S2_OUT - DMA2_ST2_CH6 DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT - DMA1_ST7_CH5 DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST2_CH5 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA2_ST2_CH0 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S5_OUT - DMA2_ST4_CH7 DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA2_ST7_CH7 DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP-DMA1_ST6_CH3 diff --git a/src/main/target/KAKUTEF4WING/target.h b/src/main/target/KAKUTEF4WING/target.h index cb29473d06a..70eb125646a 100644 --- a/src/main/target/KAKUTEF4WING/target.h +++ b/src/main/target/KAKUTEF4WING/target.h @@ -140,7 +140,7 @@ // *************** Battery Voltage Sense*********** #define USE_ADC #define ADC_INSTANCE ADC1 -#define ADC1_DMA_STREAM DMA2_Stream4 +#define ADC1_DMA_STREAM DMA2_Stream0 #define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_2_PIN PC1 #define VBAT_ADC_CHANNEL ADC_CHN_1 From c1227fa858090013be6b52de8bc26677b8c706b7 Mon Sep 17 00:00:00 2001 From: Sensei Date: Mon, 8 Jul 2024 22:48:11 -0500 Subject: [PATCH 086/212] Update OSD.md - List all of the OSD-related docs --- docs/OSD.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/docs/OSD.md b/docs/OSD.md index d57da7e25f3..5787496687a 100644 --- a/docs/OSD.md +++ b/docs/OSD.md @@ -2,6 +2,15 @@ The On Screen Display, or OSD, is a feature that overlays flight data over the video image. This can be done on the flight controller, using the analogue MAX7456 chip. Digital systems take the OSD data, via MSP DisplayPort, send it to the video receiver; which combines the data with the image. You can specify what elements are displayed, and their locations on the image. Most systems are character based, and use the MAX7456 analogue setup, or MSP DisplayPort. However, there are some different systems which are also supported. Such as the canvas based FrSKY PixelOSD on analogue. Canvas OSDs draw shapes on the image. Whereas character based OSDs use font characters to display the data. + +General OSD information is in this document. Other documents cover specific OSD-related topics: +* [Custom OSD Messages](https://github.com/iNavFlight/inav/wiki/OSD-custom-messages) +* [OSD Hud and ESP32 radars](https://github.com/iNavFlight/inav/wiki/OSD-Hud-and-ESP32-radars) +* [OSD Joystick](https://github.com/iNavFlight/inav/blob/master/docs/OSD%20Joystick.md) +* [DJI compatible OSD.md](https://github.com/iNavFlight/inav/blob/master/docs/DJI%20compatible%20OSD.md) +* [Pixel OSD FAQ](https://github.com/iNavFlight/inav/wiki/Pixel-OSD-FAQs) + + ## Features and Limitations Not all OSDs are created equally. This table shows the differences between the different systems available. From 72327a6812502fc3a89d926fbdcb055cd2251575 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 9 Jul 2024 17:43:52 +0200 Subject: [PATCH 087/212] UBLOX and UBLOX7 have been merged into UBLOX Any difference between UBLOX and UBLOX7 is now handled based on GPS protocol version, and not INAV GPS Provider type. --- src/main/fc/settings.yaml | 2 +- src/main/io/gps.h | 1 - src/main/io/gps_ublox.c | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 6670148d0bd..b8ab782ee96 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -42,7 +42,7 @@ tables: values: ["VELNED", "TURNRATE","ADAPTIVE"] enum: imu_inertia_comp_method_e - name: gps_provider - values: ["UBLOX", "UBLOX7", "MSP", "FAKE"] + values: ["UBLOX", "MSP", "FAKE"] enum: gpsProvider_e - name: gps_sbas_mode values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"] diff --git a/src/main/io/gps.h b/src/main/io/gps.h index 7b78fe5e799..c14db4a7630 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -34,7 +34,6 @@ typedef enum { GPS_UBLOX = 0, - GPS_UBLOX7PLUS, GPS_MSP, GPS_FAKE, GPS_PROVIDER_COUNT diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 725ecfd862d..acc894996ba 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1224,7 +1224,7 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread) ptSemaphoreWait(semNewDataReady); gpsProcessNewSolutionData(false); - if ((gpsState.gpsConfig->autoConfig) && (gpsState.gpsConfig->provider == GPS_UBLOX || gpsState.gpsConfig->provider == GPS_UBLOX7PLUS)) { + if ((gpsState.gpsConfig->autoConfig) && (gpsState.gpsConfig->provider == GPS_UBLOX)) { if ((millis() - gpsState.lastCapaPoolMs) > GPS_CAPA_INTERVAL) { gpsState.lastCapaPoolMs = millis(); From e8fd649a6f9f639cdc0ebe64d8c044d68b484078 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 9 Jul 2024 17:59:27 +0200 Subject: [PATCH 088/212] Missed commit --- src/main/io/gps.c | 7 ------- src/main/io/gps_ublox.c | 2 +- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 294b9414297..e7aecd3e0d6 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -102,13 +102,6 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { { false, 0, NULL, NULL }, #endif - /* UBLOX7PLUS binary */ -#ifdef USE_GPS_PROTO_UBLOX - { false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX }, -#else - { false, 0, NULL, NULL }, -#endif - /* MSP GPS */ #ifdef USE_GPS_PROTO_MSP { true, 0, &gpsRestartMSP, &gpsHandleMSP }, diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index acc894996ba..4e32628a017 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1271,7 +1271,7 @@ void gpsHandleUBLOX(void) bool isGpsUblox(void) { - if(gpsState.gpsPort != NULL && (gpsState.gpsConfig->provider == GPS_UBLOX || gpsState.gpsConfig->provider == GPS_UBLOX7PLUS)) { + if(gpsState.gpsPort != NULL && (gpsState.gpsConfig->provider == GPS_UBLOX)) { return true; } From e6e903a076fbbc4f46e0ad84a35ad69b4c20e293 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 9 Jul 2024 18:12:25 +0200 Subject: [PATCH 089/212] No need to check provider. --- src/main/io/gps_ublox.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 4e32628a017..89549768edb 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -1224,7 +1224,7 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread) ptSemaphoreWait(semNewDataReady); gpsProcessNewSolutionData(false); - if ((gpsState.gpsConfig->autoConfig) && (gpsState.gpsConfig->provider == GPS_UBLOX)) { + if (gpsState.gpsConfig->autoConfig) { if ((millis() - gpsState.lastCapaPoolMs) > GPS_CAPA_INTERVAL) { gpsState.lastCapaPoolMs = millis(); From 442aaad0a06d2f98dd18520cfb93db22bf02f7ec Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 9 Jul 2024 23:17:51 +0200 Subject: [PATCH 090/212] Quick and dirty attemp at making things play along --- src/main/telemetry/mavlink.c | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 6b4c9346ece..59d1ef69463 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -162,6 +162,7 @@ static serialPortConfig_t *portConfig; static bool mavlinkTelemetryEnabled = false; static portSharing_e mavlinkPortSharing; +static uint8_t txbuff_free = 100; /* MAVLink datastream rates in Hz */ static uint8_t mavRates[] = { @@ -1111,6 +1112,13 @@ static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) { return true; } +static bool handleIncoming_RADIO_STATUS(void) { + mavlink_radio_status_t msg; + mavlink_msg_radio_status_decode(&mavRecvMsg, &msg); + txbuff_free = msg.txbuf; + return true; +} + #ifdef USE_ADSB static bool handleIncoming_ADSB_VEHICLE(void) { mavlink_adsb_vehicle_t msg; @@ -1181,6 +1189,8 @@ static bool processMAVLinkIncomingTelemetry(void) case MAVLINK_MSG_ID_ADSB_VEHICLE: return handleIncoming_ADSB_VEHICLE(); #endif + case MAVLINK_MSG_ID_RADIO_STATUS: + return handleIncoming_RADIO_STATUS(); default: return false; } @@ -1207,7 +1217,7 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs) incomingRequestServed = true; } - if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) { + if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY && txbuff_free >= 90) { // Only process scheduled data if we didn't serve any incoming request this cycle if (!incomingRequestServed || ( From 26af58c3609d2eb91ae1b69ec268833ab1fd8368 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 10 Jul 2024 11:46:38 +0200 Subject: [PATCH 091/212] All all baro to IFLIGHTF4_SUCCEXD --- src/main/target/IFLIGHTF4_SUCCEXD/target.h | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h index 6ba059bb63c..6db93702c42 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.h +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.h @@ -39,6 +39,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + // *************** SPI2 OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 @@ -91,9 +96,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 +#define USE_BARO_ALL #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 From 0c6d79ed266c42ef73ad7e9ae7190032395f63bc Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 12:42:42 +0200 Subject: [PATCH 092/212] Remove mention of UBLOX7. --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index a217a26a981..b599a739776 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1594,7 +1594,7 @@ Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS pos ### gps_provider -Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). +Which GPS protocol to be used. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b8ab782ee96..eb0c9806b42 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1666,7 +1666,7 @@ groups: condition: USE_GPS members: - name: gps_provider - description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." + description: "Which GPS protocol to be used." default_value: "UBLOX" field: provider table: gps_provider From 964c9d495e0f0787947f68450104ef6ab01361b1 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 12:49:43 +0200 Subject: [PATCH 093/212] Another mention of UBLOX7 squashed --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index b599a739776..da0b77f8ce1 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1614,7 +1614,7 @@ Which SBAS mode to be used ### gps_ublox_nav_hz -Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer. +Navigation update rate for UBLOX receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index eb0c9806b42..52d6d63f66e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1721,7 +1721,7 @@ groups: min: 5 max: 10 - name: gps_ublox_nav_hz - description: "Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer." + description: "Navigation update rate for UBLOX receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer." default_value: 10 field: ubloxNavHz type: uint8_t From 0c54990ca70fdfa89526a7ab2424cd1b21000967 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 14:58:39 +0200 Subject: [PATCH 094/212] create single zip with all hex files, again. --- .github/workflows/ci.yml | 35 ++++++++++++++++++++++++++++++++++- 1 file changed, 34 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 92862bb4300..06d0c437809 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -49,8 +49,41 @@ jobs: - name: Upload artifacts uses: actions/upload-artifact@v4 with: - name: ${{ env.BUILD_NAME }}.${{ matrix.id }} + name: matrix-${{ env.BUILD_NAME }}.${{ matrix.id }} path: ./build/*.hex + retention-days: 1 + + upload-artifacts: + runs-on: ubuntu-latest + needs: [build] + steps: + - name: Setup environment + env: + ACTIONS_ALLOW_UNSECURE_COMMANDS: true + run: | + # This is the hash of the commit for the PR + # when the action is triggered by PR, empty otherwise + COMMIT_ID=${{ github.event.pull_request.head.sha }} + # This is the hash of the commit when triggered by push + # but the hash of refs/pull//merge, which is different + # from the hash of the latest commit in the PR, that's + # why we try github.event.pull_request.head.sha first + COMMIT_ID=${COMMIT_ID:-${{ github.sha }}} + BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID}) + VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') + echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + - name: Download artifacts + uses: actions/download-artifact@v4 + with: + name: matrix-inav-* + merge-multiple: true + path: binaries + - name: Upload single zip + uses: actions/upload-artifact@v4 + with: + name: ${{ env.BUILD_NAME }} + path: binaries/*.hex build-SITL-Linux: runs-on: ubuntu-latest From 5c42ec792e1c58f28f016cced963625af61f14ba Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 15:09:33 +0200 Subject: [PATCH 095/212] Another attempt --- .github/workflows/ci.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 06d0c437809..d63e3daf2e3 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -57,6 +57,7 @@ jobs: runs-on: ubuntu-latest needs: [build] steps: + - uses: actions/checkout@v4 - name: Setup environment env: ACTIONS_ALLOW_UNSECURE_COMMANDS: true From a856c84c52c90844b323f1a070d0cec8b68ab2d8 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 15:21:02 +0200 Subject: [PATCH 096/212] s/name/pattern/ --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index d63e3daf2e3..15c0e872f0f 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -77,7 +77,7 @@ jobs: - name: Download artifacts uses: actions/download-artifact@v4 with: - name: matrix-inav-* + pattern: matrix-inav-* merge-multiple: true path: binaries - name: Upload single zip From a330d2503c973f39a4a375ba5a746cb7b8e5c2b4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 15:24:10 +0200 Subject: [PATCH 097/212] Generate targets list --- .github/workflows/ci.yml | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 15c0e872f0f..0c7f795e0bc 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -80,11 +80,19 @@ jobs: pattern: matrix-inav-* merge-multiple: true path: binaries - - name: Upload single zip + - name: Build target list + run: | + ls -1 binaries/*.hex > targets.txt + - name: Upload firmware images uses: actions/upload-artifact@v4 with: name: ${{ env.BUILD_NAME }} path: binaries/*.hex + - name: Upload firmware images + uses: actions/upload-artifact@v4 + with: + name: targets + path: targets.txt build-SITL-Linux: runs-on: ubuntu-latest From 819591e706045f071f266bf10c431e63256533c1 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 10 Jul 2024 15:43:22 +0200 Subject: [PATCH 098/212] remove binaries/ from path --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 0c7f795e0bc..4663febe50e 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -82,7 +82,7 @@ jobs: path: binaries - name: Build target list run: | - ls -1 binaries/*.hex > targets.txt + ls -1 binaries/*.hex | cut -d/ -f2 > targets.txt - name: Upload firmware images uses: actions/upload-artifact@v4 with: From 6a3a0d1bf3663d6de7fa880706ea18110c60e6a7 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 11 Jul 2024 00:05:50 +0200 Subject: [PATCH 099/212] First attempt at transmitting telemetry May need to break out the osciloscope/logic analizer soon. --- src/main/build/debug.h | 1 + src/main/fc/cli.c | 4 +++- src/main/fc/settings.yaml | 2 +- src/main/rx/sbus.c | 2 +- src/main/telemetry/sbus2.c | 48 +++++++++++++++++++++++++++----------- src/main/telemetry/sbus2.h | 6 +++-- 6 files changed, 45 insertions(+), 18 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 0d897f77101..0bb74bac1ac 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -78,6 +78,7 @@ typedef enum { DEBUG_HEADTRACKING, DEBUG_GPS, DEBUG_LULU, + DEBUG_SBUS2, DEBUG_COUNT // also update debugModeNames in cli.c } debugType_e; diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 580859fec0c..0ea43fd0ce7 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -211,7 +211,9 @@ static const char *debugModeNames[DEBUG_COUNT] = { "POS_EST", "ADAPTIVE_FILTER", "HEADTRACKER", - "GPS" + "GPS", + "LULU", + "SBUS2" }; /* Sensor names (used in lookup tables for *_hardware settings and in status diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9e68ec1778d..b0a0fb70ea7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE", "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", - "ADAPTIVE_FILTER", "HEADTRACKER", "GPS", "LULU"] + "ADAPTIVE_FILTER", "HEADTRACKER", "GPS", "LULU", "SBUS2"] - name: aux_operator values: ["OR", "AND"] enum: modeActivationOperator_e diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 8a5c3f926a1..3d08d274333 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -199,7 +199,7 @@ static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeC ); #ifdef USE_TELEMETRY - if (portShared) { + if (portShared || (rxConfig->serialrx_provider == SERIALRX_SBUS2)) { telemetrySharedPort = sBusPort; } #endif diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index ed258ee15f4..c00a3a1d0da 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -24,45 +24,67 @@ #include "common/utils.h" #include "common/time.h" +#include "telemetry/telemetry.h" #include "telemetry/sbus2.h" #include "rx/sbus.h" #ifdef USE_SBUS2_TELEMETRY -const uint8_t sbus2SlotIds[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = { - {0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3}, - {0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3}, - {0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB}, - {0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB} +const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { + 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, + 0x13, 0x93, 0x53, 0xD3, 0x33, 0xB3, 0x73, 0xF3, + 0x0B, 0x8B, 0x4B, 0xCB, 0x2B, 0xAB, 0x6B, 0xEB, + 0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB }; -sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; -uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS] = {{}}; +sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT] = {}; +uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT] = {}; +timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT] = {}; void handleSbus2Telemetry(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); + // TODO: placeholder + + int16_t temp = 42 | 0x4000; + sbusTelemetryData[0].payload.temp125.tempHigh = ((temp >> 8) & 0xFF); + sbusTelemetryData[0].payload.temp125.tempLow = (temp & 0xFF); + sbusTelemetryDataUsed[0] = 1; + + int16_t rpm = 9000; + sbusTelemetryData[1].payload.rpm.rpmHigh = (rpm >> 8) & 0xFF; + sbusTelemetryData[1].payload.rpm.rpmLow = rpm & 0xFF; + sbusTelemetryDataUsed[1] = 1; + // P1S0: TEMP + // P1S1: RPM // update telemetry info } void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { + if(!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || rxConfig()->serialrx_provider != SERIALRX_SBUS2) + { + return; + } + uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); uint8_t lastFrame = sbusGetLastFrameTime(); timeUs_t elapsedTime = currentTimeUs - lastFrame - MS2US(2); // 2ms after sbus2 frame = slot 0 // +660us for next slot - if(elapsedTime > 0) { + if(elapsedTime > MS2US(2)) { uint8_t slot = elapsedTime % 660; - if(slot < SBUS2_TELEMETRY_SLOTS) { - if(sbusTelemetryDataStatus[telemetryPage][slot] != 0) { - sbusTelemetryData[telemetryPage][slot].slotId = sbus2SlotIds[telemetryPage][slot]; - // send - sbusTelemetryDataStatus[telemetryPage][slot] = 0; + int slotIndex = (telemetryPage * SBUS2_TELEMETRY_SLOTS) + slot; + if(slot < SBUS2_TELEMETRY_SLOTS && slotIndex < SBUS2_SLOT_COUNT && (currentTimeUs - sbusTelemetryDataLastSent[slotIndex]) > MS2US(2)) { + if(sbusTelemetryDataUsed[slotIndex] != 0) { + sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; + // send + serialWriteBuf(telemetrySharedPort, (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); + sbusTelemetryDataLastSent[slotIndex] = currentTimeUs; } } } diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 7e59782a1d1..9fdbc3fd7db 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -27,6 +27,7 @@ #define SBUS2_TELEMETRY_ITEM_SIZE 3 #define SBUS2_TELEMETRY_SLOTS 8 #define SBUS2_TELEMETRY_PAGES 4 + #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) #if defined(USE_TELEMETRY) && defined(USE_SBUS2_TELEMETRY) @@ -105,8 +106,9 @@ typedef struct sbus2_telemetry_frame_s { } __attribute__((packed)) sbus2_telemetry_frame_t; extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; -extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; -extern uint8_t sbusTelemetryDataStatus[SBUS2_TELEMETRY_PAGES][SBUS2_TELEMETRY_SLOTS]; +extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT]; +extern uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT]; +extern timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT]; // refresh telemetry buffers void handleSbus2Telemetry(timeUs_t currentTimeUs); From ff94b7702e8a8f7ced8b487eb875c346b5c383d0 Mon Sep 17 00:00:00 2001 From: MUSTARDTIGERFPV Date: Thu, 11 Jul 2024 04:17:34 +0000 Subject: [PATCH 100/212] Improve MAVLink behavior when flow control information is available --- src/main/telemetry/mavlink.c | 63 +++++++++++++++++++++++------------- 1 file changed, 41 insertions(+), 22 deletions(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 59d1ef69463..be10ad1fd95 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -163,14 +163,15 @@ static serialPortConfig_t *portConfig; static bool mavlinkTelemetryEnabled = false; static portSharing_e mavlinkPortSharing; static uint8_t txbuff_free = 100; +static bool txbuff_valid = false; /* MAVLink datastream rates in Hz */ static uint8_t mavRates[] = { [MAV_DATA_STREAM_EXTENDED_STATUS] = 2, // 2Hz - [MAV_DATA_STREAM_RC_CHANNELS] = 5, // 5Hz + [MAV_DATA_STREAM_RC_CHANNELS] = 1, // 1Hz [MAV_DATA_STREAM_POSITION] = 2, // 2Hz - [MAV_DATA_STREAM_EXTRA1] = 10, // 10Hz - [MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz + [MAV_DATA_STREAM_EXTRA1] = 3, // 3Hz + [MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz, HEARTBEATs are important [MAV_DATA_STREAM_EXTRA3] = 1 // 1Hz }; @@ -1112,9 +1113,23 @@ static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) { return true; } +static bool handleIncoming_PARAM_REQUEST_LIST(void) { + mavlink_param_request_list_t msg; + mavlink_msg_param_request_list_decode(&mavRecvMsg, &msg); + + // Respond that we don't have any parameters to force Mission Planner to give up quickly + if (msg.target_system == mavSystemId) { + // mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); + mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0); + mavlinkSendMessage(); + } + return true; +} + static bool handleIncoming_RADIO_STATUS(void) { mavlink_radio_status_t msg; mavlink_msg_radio_status_decode(&mavRecvMsg, &msg); + txbuff_valid = true; txbuff_free = msg.txbuf; return true; } @@ -1163,6 +1178,7 @@ static bool handleIncoming_ADSB_VEHICLE(void) { } #endif +// Returns whether a message was processed static bool processMAVLinkIncomingTelemetry(void) { while (serialRxBytesWaiting(mavlinkPort) > 0) { @@ -1173,6 +1189,8 @@ static bool processMAVLinkIncomingTelemetry(void) switch (mavRecvMsg.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: break; + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: + return handleIncoming_PARAM_REQUEST_LIST(); case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: return handleIncoming_MISSION_CLEAR_ALL(); case MAVLINK_MSG_ID_MISSION_COUNT: @@ -1184,13 +1202,17 @@ static bool processMAVLinkIncomingTelemetry(void) case MAVLINK_MSG_ID_MISSION_REQUEST: return handleIncoming_MISSION_REQUEST(); case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: - return handleIncoming_RC_CHANNELS_OVERRIDE(); + handleIncoming_RC_CHANNELS_OVERRIDE(); + // Don't set that we handled a message, otherwise RC channel packets will block telemetry messages + return false; #ifdef USE_ADSB case MAVLINK_MSG_ID_ADSB_VEHICLE: return handleIncoming_ADSB_VEHICLE(); #endif case MAVLINK_MSG_ID_RADIO_STATUS: - return handleIncoming_RADIO_STATUS(); + handleIncoming_RADIO_STATUS(); + // Don't set that we handled a message, otherwise radio status packets will block telemetry messages + return false; default: return false; } @@ -1202,8 +1224,6 @@ static bool processMAVLinkIncomingTelemetry(void) void handleMAVLinkTelemetry(timeUs_t currentTimeUs) { - static bool incomingRequestServed; - if (!mavlinkTelemetryEnabled) { return; } @@ -1212,24 +1232,23 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs) return; } - // If we did serve data on incoming request - skip next scheduled messages batch to avoid link clogging - if (processMAVLinkIncomingTelemetry()) { - incomingRequestServed = true; + // Process incoming MAVLink - ignore the return indicating whether or not a message was processed + // Very few telemetry links are dynamic uplink/downlink split so uplink telemetry shouldn't reduce downlink bandwidth availability + processMAVLinkIncomingTelemetry(); + + // Determine whether to send telemetry back + bool shouldSendTelemetry = false; + if (txbuff_valid) { + // Use flow control if available + shouldSendTelemetry = txbuff_free >= 33; + } else { + // If not, use blind frame pacing + shouldSendTelemetry = (currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY; } - if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY && txbuff_free >= 90) { - // Only process scheduled data if we didn't serve any incoming request this cycle - if (!incomingRequestServed || - ( - (rxConfig()->receiverType == RX_TYPE_SERIAL) && - (rxConfig()->serialrx_provider == SERIALRX_MAVLINK) && - !tristateWithDefaultOnIsActive(rxConfig()->halfDuplex) - ) - ) { - processMAVLinkTelemetry(currentTimeUs); - } + if (shouldSendTelemetry) { + processMAVLinkTelemetry(currentTimeUs); lastMavlinkMessage = currentTimeUs; - incomingRequestServed = false; } } From 3d1e6832c5f01be1c854ba369a1c7533702d7dbf Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 11 Jul 2024 20:33:27 +0200 Subject: [PATCH 101/212] "working" need to fill in actual telemetry values now. --- src/main/fc/fc_tasks.c | 5 +- src/main/rx/sbus.c | 17 +- src/main/rx/sbus.h | 5 +- src/main/target/common.h | 6 +- src/main/telemetry/sbus2.c | 794 +++++++++++++++++++++++++++++++-- src/main/telemetry/sbus2.h | 173 ++++--- src/main/telemetry/telemetry.c | 6 +- 7 files changed, 906 insertions(+), 100 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 5728b9752cd..b269681baa7 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -93,6 +93,7 @@ #include "sensors/opflow.h" #include "telemetry/telemetry.h" +#include "telemetry/sbus2.h" #include "config/feature.h" @@ -438,7 +439,7 @@ void fcTasksInit(void) #endif #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) - setTaskEnabled(TASK_TELEMETRY_SBUS2, rxConfig->serialrx_provider == SERIALRX_SBUS2); + setTaskEnabled(TASK_TELEMETRY_SBUS2,rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_SBUS2); #endif #ifdef USE_ADAPTIVE_FILTER @@ -734,7 +735,7 @@ cfTask_t cfTasks[TASK_COUNT] = { [TASK_TELEMETRY_SBUS2] = { .taskName = "SBUS2_TELEMETRY", .taskFunc = taskSendSbus2Telemetry, - .desiredPeriod = TASK_PERIOD_US(300), + .desiredPeriod = TASK_PERIOD_HZ(2000), .staticPriority = TASK_PRIORITY_IDLE, }, #endif diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 3d08d274333..e8f67522b77 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -67,6 +67,7 @@ typedef struct sbusFrameData_s { } sbusFrameData_t; static uint8_t sbus2ActiveTelemetryPage = 0; +static uint8_t sbus2ActiveTelemetrySlot = 0; timeUs_t frameTime = 0; // Receive ISR callback @@ -76,6 +77,7 @@ static void sbusDataReceive(uint16_t c, void *data) const timeUs_t currentTimeUs = micros(); const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs); sbusFrameData->lastActivityTimeUs = currentTimeUs; + bool isSbus2Frame = true; // Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { @@ -108,8 +110,10 @@ static void sbusDataReceive(uint16_t c, void *data) if(frame->endByte & 0x4) { sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF; frameTime = currentTimeUs; + isSbus2Frame = true; } else { sbus2ActiveTelemetryPage = 0; + sbus2ActiveTelemetrySlot = 0; frameTime = -1; } @@ -153,6 +157,8 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) // Reset the frameDone flag - tell ISR that we're ready to receive next frame sbusFrameData->frameDone = false; + //taskSendSbus2Telemetry(micros()); + // Calculate "virtual link quality based on packet loss metric" if (retValue & RX_FRAME_COMPLETE) { lqTrackerAccumulate(rxRuntimeConfig->lqTracker, ((retValue & RX_FRAME_DROPPED) || (retValue & RX_FRAME_FAILSAFE)) ? 0 : RSSI_MAX_VALUE); @@ -217,11 +223,18 @@ bool sbusInitFast(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig return sbusInitEx(rxConfig, rxRuntimeConfig, SBUS_BAUDRATE_FAST); } -#if defined(USE_TELEMETRY) && defined(USE_SBUS2_TELEMETRY) -uint8_t sbusGetLastFrameTime(void) { +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) +timeUs_t sbusGetLastFrameTime(void) { return frameTime; } +uint8_t sbusGetCurrentTelemetryNextSlot(void) +{ + uint8_t current = sbus2ActiveTelemetrySlot; + sbus2ActiveTelemetrySlot++; + return current; +} + uint8_t sbusGetCurrentTelemetryPage(void) { return sbus2ActiveTelemetryPage; } diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index b3356ace83e..aa550b618e1 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -24,7 +24,8 @@ bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); -#ifdef USE_SBUS2_TELEMETRY +#ifdef USE_TELEMETRY_SBUS2 uint8_t sbusGetCurrentTelemetryPage(void); -uint8_t sbusGetLastFrameTime(void); +uint8_t sbusGetCurrentTelemetryNextSlot(void); +timeUs_t sbusGetLastFrameTime(void); #endif diff --git a/src/main/target/common.h b/src/main/target/common.h index 3238abea018..51f1fbf6ea6 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -195,9 +195,9 @@ #define USE_HEADTRACKER_SERIAL #define USE_HEADTRACKER_MSP -#ifndef STM32F4 -// needs bi-direction inverter, no available on F4 hardware. -#define USE_SBUS2_TELEMETRY +#if defined(STM32F7) || defined(STM32H7) +// needs bi-direction inverter, not available on F4 hardware. +#define USE_TELEMETRY_SBUS2 #endif //Designed to free space of F722 and F411 MCUs diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index c00a3a1d0da..5cb6e40f276 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -29,7 +29,7 @@ #include "rx/sbus.h" -#ifdef USE_SBUS2_TELEMETRY +#ifdef USE_TELEMETRY_SBUS2 const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { 0x03, 0x83, 0x43, 0xC3, 0x23, 0xA3, 0x63, 0xE3, @@ -39,9 +39,10 @@ const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { }; + sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT] = {}; uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT] = {}; -timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT] = {}; +timeUs_t sbusTelemetryMinDelay[SBUS2_SLOT_COUNT] = {}; void handleSbus2Telemetry(timeUs_t currentTimeUs) { @@ -49,45 +50,788 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) // TODO: placeholder - int16_t temp = 42 | 0x4000; - sbusTelemetryData[0].payload.temp125.tempHigh = ((temp >> 8) & 0xFF); - sbusTelemetryData[0].payload.temp125.tempLow = (temp & 0xFF); - sbusTelemetryDataUsed[0] = 1; + for (int i = 1; i < SBUS2_SLOT_COUNT; ++i) { + int16_t temp = 41 + i; + send_SBS01T(i, temp); + } - int16_t rpm = 9000; - sbusTelemetryData[1].payload.rpm.rpmHigh = (rpm >> 8) & 0xFF; - sbusTelemetryData[1].payload.rpm.rpmLow = rpm & 0xFF; - sbusTelemetryDataUsed[1] = 1; - // P1S0: TEMP - // P1S1: RPM - // update telemetry info + DEBUG_SET(DEBUG_SBUS2, 5, 42); +} + + +#define SBUS2_DEADTIME MS2US(2) +#define SBUS2_SLOT_TIME 700 +#define SBUS2_SLOT_DELAY_MAX 200 +uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) +{ + if (elapsed < SBUS2_DEADTIME) { + return 0xFF; // skip it + } + + elapsed = elapsed - SBUS2_DEADTIME; + + uint8_t slot = (elapsed % SBUS2_SLOT_TIME) - 1; + + if (elapsed - (slot * SBUS2_SLOT_TIME) > SBUS2_SLOT_DELAY_MAX) { + slot = 0xFF; + } + + return slot; } void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { - if(!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || rxConfig()->serialrx_provider != SERIALRX_SBUS2) - { + if (!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || + rxConfig()->serialrx_provider != SERIALRX_SBUS2) { + DEBUG_SET(DEBUG_SBUS2, 0, -1); return; } + timeUs_t elapsedTime = currentTimeUs - sbusGetLastFrameTime(); + + if(elapsedTime > MS2US(8)) { + DEBUG_SET(DEBUG_SBUS2, 0, -2); + return; + } + + DEBUG_SET(DEBUG_SBUS2, 0, 1); + uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); - uint8_t lastFrame = sbusGetLastFrameTime(); - timeUs_t elapsedTime = currentTimeUs - lastFrame - MS2US(2); - // 2ms after sbus2 frame = slot 0 - // +660us for next slot - if(elapsedTime > MS2US(2)) { - uint8_t slot = elapsedTime % 660; + uint8_t slot = sbus2GetTelemetrySlot(elapsedTime); + + if(slot < SBUS2_TELEMETRY_SLOTS) { + DEBUG_SET(DEBUG_SBUS2, 1, telemetryPage); + DEBUG_SET(DEBUG_SBUS2, 2, slot); + DEBUG_SET(DEBUG_SBUS2, 4, -1); int slotIndex = (telemetryPage * SBUS2_TELEMETRY_SLOTS) + slot; - if(slot < SBUS2_TELEMETRY_SLOTS && slotIndex < SBUS2_SLOT_COUNT && (currentTimeUs - sbusTelemetryDataLastSent[slotIndex]) > MS2US(2)) { - if(sbusTelemetryDataUsed[slotIndex] != 0) { + if (slotIndex < SBUS2_SLOT_COUNT) { + DEBUG_SET(DEBUG_SBUS2, 3, slotIndex); + if (sbusTelemetryDataUsed[slotIndex] != 0 && sbusTelemetryMinDelay[slotIndex] < currentTimeUs) { sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; // send - serialWriteBuf(telemetrySharedPort, (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); - sbusTelemetryDataLastSent[slotIndex] = currentTimeUs; + serialWriteBuf(telemetrySharedPort, + (const uint8_t *)&sbusTelemetryData[slotIndex], + sizeof(sbus2_telemetry_frame_t)); + sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(2); + sbusTelemetryDataUsed[slotIndex] = 0; + + DEBUG_SET(DEBUG_SBUS2, 4, slotIndex); } } } } +// +void send_RPM(uint8_t port, uint32_t RPM) +{ + uint32_t value = 0; + uint8_t bytes[2] = { }; + + value = RPM / 6; + if(value > 0xffff){ + value = 0xffff; + } + bytes[1] = value >> 8; + bytes[0] = value; + SBUS2_transmit_telemetry_data( port , bytes); +} + + +void send_temp125(uint8_t port, int16_t temp) +{ + int16_t value= 0; + uint8_t bytes[2] = { }; + + value = temp | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); +} +void send_SBS01T(uint8_t port, int16_t temp){ + int16_t value= 0; + uint8_t bytes[2] = {}; + + value = temp | 0x8000; + value = value + 100; + bytes[0] = value;// >> 8; + bytes[1] = value >> 8; + SBUS2_transmit_telemetry_data( port , bytes); +} + + +void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2) +{ + uint16_t value = 0; + uint8_t bytes[2] = { }; + + // VOLTAGE1 + value = voltage1 | 0x8000; + if ( value > 0x9FFF ){ + value = 0x9FFF; // max voltage is 819.1 + } + else if(value < 0x8000){ + value = 0x8000; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //VOLTAGE2 + value = voltage2; + if ( value > 0x1FFF ){ + value = 0x1FFF; // max voltage is 819.1 + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+1 , bytes); +} + +void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage) +{ + uint16_t value = 0; + uint32_t local = 0; + uint8_t bytes[2] = { }; + + + // CURRENT + local = ((uint32_t)current) * 1 ; + value = (uint16_t)local; + if ( value > 0x3FFF ) + { + // max current is 163.83 + value = 0x3FFF; + } + bytes[0] = value >> 8; + bytes[0] = bytes[0] | 0x40; + bytes[0] = bytes[0] & 0x7F; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //VOLTAGE + local = ((uint32_t)voltage) * 1; + value = (uint16_t)local; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+1 , bytes); + + // CAPACITY + local = (uint32_t)capacity; + value = (uint16_t)local; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+2 , bytes); +} + +void send_f1675_gps(uint8_t port, uint16_t speed, int16_t altitude, int16_t vario, int32_t latitude, int32_t longitude) +{ + uint16_t value1 = 0; + int16_t value2 = 0; + uint32_t value3 = 0; + bool latitude_pos = false; + bool longitude_pos = false; + uint8_t bytes[2] = {}; + + + // SPEED -> Bit 14(bytes[1] bit7) -> GPS Valid or not + value1 = speed | 0x4000; + if (value1 > 0x43E7 ){ + value1 = 0x43E7; // max Speed is 999 km/h + } + else if( value1 < 0x4000){ + value1 = 0x4000; + } + bytes[0] = value1 >> 8; + bytes[1] = value1; + SBUS2_transmit_telemetry_data( port , bytes); + + //HIGHT + value2 = altitude | 0x4000; + /*if(value2 > 0x7FFF ){ // max = +16383 + value2 = 0x7FFF; + } + else if( value2 < 0xC000){ // min = -16384 + value2 = 0xC000; + }*/ + bytes[0] = value2 >> 8; + bytes[1] = value2; + SBUS2_transmit_telemetry_data( port+1 , bytes); + + //TIME -> 12:34:56 Uhr = 12*60*60 + 34*60 + 56 = 45296 = 0xB0F0 + bytes[0] = 0xB0; + bytes[1] = 0xF0; + SBUS2_transmit_telemetry_data( port+2 , bytes); + + // VARIO + value2 = vario * 10; + bytes[0] = value2 >> 8; + bytes[1] = value2; + SBUS2_transmit_telemetry_data( port+3 , bytes); + + // LATITUDE + if(latitude >= 0){ + latitude_pos = true; + } + else{ + latitude_pos = false; + latitude = latitude * -1; + } + bytes[0] = (uint8_t)(latitude/1000000); + value3 = (uint32_t)(latitude%1000000); + if(latitude_pos){ + bytes[1] = ((value3 >> 16) & 0x0f); // North + } + else{ + bytes[1] = ((value3 >> 16) | 0x1f); // South + } + SBUS2_transmit_telemetry_data( port+4 , bytes); + + bytes[0] = ((value3 >> 8) & 0xff); + bytes[1] = value3 & 0xff; + SBUS2_transmit_telemetry_data( port+5 , bytes); + + // LONGITUDE + if(longitude >= 0){ + longitude_pos = true; + } + else{ + longitude_pos = false; + longitude = longitude * -1; + } + bytes[0] = (uint8_t)(longitude/1000000); + value3 = (uint32_t)(longitude%1000000); + if(longitude_pos){ + bytes[1] = ((value3 >> 16) & 0x0f); // Eath + } + else{ + bytes[1] = ((value3 >> 16) | 0x1f); // West + } + SBUS2_transmit_telemetry_data( port+6 , bytes); + + bytes[0] = ((value3 >> 8) & 0xff); + bytes[1] = value3 & 0xff; + SBUS2_transmit_telemetry_data( port+7 , bytes); +} + +void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario) +{ + int16_t value = 0; + uint8_t bytes[2] = { }; + + // VARIO + value = vario; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port, bytes); + + //HIGHT + value = altitude | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1, bytes); +} + +void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario) +{ + int16_t value = 0; + uint8_t bytes[2] = { }; + + // VARIO + value = vario; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //HIGHT + value = altitude | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + +} + + +void send_SBS01TE(uint8_t port, int16_t temp){ + send_temp125(port, temp); +} +void send_F1713(uint8_t port, int16_t temp){ + send_temp125(port, temp); +} + +void send_SBS01RB(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01RM(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01RO(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01R(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} + +void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ + send_s1678_current(port, current, capacity, voltage); +} +void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} +void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} +void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2){ + send_voltage(port, voltage1, voltage2); +} +void send_SBS01Vf(uint8_t port,float voltage1, float voltage2){ + send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); +} +void send_voltagef(uint8_t port,float voltage1, float voltage2){ + send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); +} +void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ + send_s1678_current(port, current, capacity, voltage); +} +void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} + +void send_f1712_variof(uint8_t port, int16_t altitude, float vario){ + send_f1712_vario(port, altitude, (int16_t)(vario * 10)); +} +void send_f1672_variof(uint8_t port, int16_t altitude, float vario){ + send_f1672_vario(port, altitude, (int16_t)(vario * 100)); +} +void send_F1712(uint8_t port, int16_t altitude, int16_t vario){ + send_f1712_vario(port, altitude, vario); +} +void send_F1712f(uint8_t port, int16_t altitude, float vario){ + send_f1712_vario(port, altitude, (int16_t)(vario * 10)); +} +void send_F1672(uint8_t port, int16_t altitude, int16_t vario){ + send_f1672_vario(port, altitude, vario); +} +void send_F1672f(uint8_t port, int16_t altitude, float vario){ + send_f1672_vario(port, altitude, (int16_t)(vario * 100)); +} + +void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min){ + bool Lat_Negative = false; + bool Lon_Negative = false; + if(lat_deg < 0){ + Lat_Negative = true; + lat_deg = lat_deg * -1; + } + if(lon_deg < 0){ + Lon_Negative = true; + lon_deg = lon_deg * -1; + } + if(lat_min < 0){ + Lat_Negative = true; + lat_min = lat_min * -1; + } + if(lon_min < 0){ + Lon_Negative = true; + lon_min = lon_min * -1; + } + int32_t _latitude_deg = lat_deg; + int32_t _longitude_deg = lon_deg; + int32_t _latitude_min = lat_min * 10000; + int32_t _longitude_min = lon_min * 10000; + int32_t _latitude = _latitude_deg * 1000000; + int32_t _longitude = _longitude_deg * 1000000; + _latitude = _latitude + _latitude_min; + _longitude = _longitude + _longitude_min; + if(Lat_Negative){ + _latitude = _latitude * -1; + } + if(Lon_Negative){ + _longitude = _longitude * -1; + } + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min){ + bool Lat_Negative = false; + bool Lon_Negative = false; + if(lat_deg < 0){ + Lat_Negative = true; + lat_deg = lat_deg * -1; + } + if(lon_deg < 0){ + Lon_Negative = true; + lon_deg = lon_deg * -1; + } + if(lat_min < 0){ + Lat_Negative = true; + lat_min = lat_min * -1; + } + if(lon_min < 0){ + Lon_Negative = true; + lon_min = lon_min * -1; + } + int32_t _latitude_deg = lat_deg; + int32_t _longitude_deg = lon_deg; + int32_t _latitude = _latitude_deg * 1000000; + int32_t _longitude = _longitude_deg * 1000000; + _latitude = _latitude + lat_min; + _longitude = _longitude + lon_min; + if(Lat_Negative){ + _latitude = _latitude * -1; + } + if(Lon_Negative){ + _longitude = _longitude * -1; + } + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude){ + int32_t _latitude = latitude; + int32_t _longitude = longitude; + int32_t _latitude_deg = _latitude/1000000; + int32_t _longitude_deg = _longitude/1000000; + int32_t _latitude_min = _latitude%1000000; + int32_t _longitude_min = _longitude%1000000; + _latitude = _latitude_deg * 1000000; + _longitude = _longitude_deg * 1000000; + _latitude = _latitude + ((_latitude_min * 60)/100); + _longitude = _longitude + ((_longitude_min * 60)/100); + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude){ + int32_t _latitude = latitude * 1000000; + int32_t _longitude = longitude * 1000000; + int32_t _latitude_deg = _latitude/1000000; + int32_t _longitude_deg = _longitude/1000000; + int32_t _latitude_min = _latitude%1000000; + int32_t _longitude_min = _longitude%1000000; + _latitude = _latitude_deg * 1000000; + _longitude = _longitude_deg * 1000000; + _latitude = _latitude + ((_latitude_min * 60)/100); + _longitude = _longitude + ((_longitude_min * 60)/100); + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_SBS10G( + uint8_t port, + uint16_t hours, // 0 to 24 + uint16_t minutes, // 0 to 60 + uint16_t seconds, // 0 to 60 + float latitude, // decimal degrees (i.e. 52.520833; negative value for southern hemisphere) + float longitude, // decimal degrees (i.e. 13.409430; negative value for western hemisphere) + float altitudeMeters, // meters (valid range: -1050 to 4600) + uint16_t speed, // km/h (valid range 0 to 511) + float gpsVario) // m/s (valid range: -150 to 260) +{ + uint32_t utc = (hours*3600) + (minutes*60) + seconds; + uint32_t lat, lon; + // scale latitude/longitude (add 0.5 for correct rounding) + if (latitude > 0) { + lat = (600000.0*latitude) + 0.5; + } + else { + lat = (-600000.0*latitude) + 0.5; + // toggle south bit + lat |= 0x4000000; + } + if (longitude > 0) { + lon = (600000.0*longitude) + 0.5; + } + else { + lon = (-600000.0*longitude) + 0.5; + // toggle west bit + lon |= 0x8000000; + } + // convert altitude (add 0.5 for correct rounding) + uint16_t alt = (altitudeMeters>=-820 && altitudeMeters<=4830) ?(1.25*(altitudeMeters+820)) + 0.5 : 0; + // error check speed + if (speed < 512) { + // set speed enable bit + speed |= 0x200; + } + else { + speed = 0; + } + // initialize buffer + uint8_t bytes[2] = { }; + // slot 0 (utc) + bytes[0] = (utc&0x00ff); + bytes[1] = (utc&0xff00)>>8; + SBUS2_transmit_telemetry_data(port , bytes); + // slot 1 (latitude & utc) + bytes[0] = ((lat&0x007f)<<1) | ((utc&0x10000)>>16); + bytes[1] = (lat&0x7f80)>>7; + SBUS2_transmit_telemetry_data(port+1 , bytes); + // slot 2 (latitude & longitude) + bytes[0] = (lat&0x07f8000)>>15; + bytes[1] = ((lat&0x7800000)>>23) | (lon&0x0f)<<4; + SBUS2_transmit_telemetry_data(port+2 , bytes); + // slot 3 (longitude) + bytes[0] = (lon&0x00ff0)>>4; + bytes[1] = (lon&0xff000)>>12; + SBUS2_transmit_telemetry_data(port+3 , bytes); + // slot 4 (longitude & speed) + bytes[0] = ((lon&0xff00000)>>20); + bytes[1] = (speed&0xff); + SBUS2_transmit_telemetry_data(port+4 , bytes); + // slot 5 (pressure & speed) + bytes[0] = ((speed&0x300)>>8); + bytes[1] = 0x00; + SBUS2_transmit_telemetry_data(port+5 , bytes); + // slot 6 (altitude & pressure) + bytes[0] = ((alt&0x003)<<6); + bytes[1] = (alt&0x3fc)>>2; + SBUS2_transmit_telemetry_data(port+6 , bytes); + // slot (7 (vario & altitude) + uint16_t vario; + // error check vario + if (gpsVario >= -150 && gpsVario <= 260) { + // scale vario (add 0.5 for correct rounding) + vario = (10.0*(gpsVario + 150)) + 0.5; + // set vario enable + vario |= 0x1000; + } + else { + vario = 0; + } + bytes[0] = ((vario&0x001f)<<3) | ((alt&0x1c00)>>10); + bytes[1] = (vario&0x1fe0)>>5; + SBUS2_transmit_telemetry_data(port+7 , bytes); +} +void send_scorpion_kontronik( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + uint32_t value = 0; + uint8_t bytes[2] = { }; + + // voltage 41.1 = 4110 + value = voltage | 0x8000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + // 1330 mah => 1.33 Ah + value = capacity; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + + // 2250 rpm => 2250 + value = rpm / 6; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 2 , bytes); + + // 13310 => 133.1 A + value = current; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 3 , bytes); + + // 41 => 41 Celsius + value = temp; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 4 , bytes); + + // 21 => Bec Celsius + value = becTemp; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 5 , bytes); + + // 650 => 6,5 Bec Current + value = becCurrent; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 6 , bytes); + + // PWM output + value = pwm; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 7 , bytes); +} + +void send_scorpion( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + send_scorpion_kontronik( + port, + voltage, + capacity, + rpm, + current, + temp, + becTemp, + becCurrent, + pwm); +} + +void send_kontronik( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + send_scorpion_kontronik( + port, + voltage, + capacity, + rpm, + current, + temp, + becTemp, + becCurrent, + pwm); +} + +void send_jetcat( + uint8_t port, + uint32_t rpm, + uint16_t egt, + uint16_t pump_volt, + uint32_t setrpm, + uint16_t thrust, + uint16_t fuel, + uint16_t fuelflow, + uint16_t altitude, + uint16_t quality, + uint16_t volt, + uint16_t current, + uint16_t speed, + uint16_t status, + uint32_t secondrpm) +{ + uint32_t value = 0; + uint8_t bytes[2] = {}; + + // Actual RPM with 0x4000 Offset -> why? + value = rpm / 100; + value = value | 0x4000; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + // EGT Abgastemperatur in °C + value = egt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + + // Pump Voltage 12.34V = 1234 + value = pump_volt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 2 , bytes); + + // Setpoint RPM without Offset + value = setrpm / 100; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 3 , bytes); + + // Thrust 123.4N = 1234 + value = thrust; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 4 , bytes); + + // Fuel (remain) in ml + value = fuel; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 5 , bytes); + + // Fuel Flow in ml/min + value = fuelflow; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 6 , bytes); + + // Altitude -> without offset? + value = altitude; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 7 , bytes); + + // Fuel Quality in % + value = quality; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 8 , bytes); + + // Voltage 12.34V = 1234 + value = volt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 9 , bytes); + + // Current 123.4A = 1234 + value = current; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 10 , bytes); + + // Speed in km/h + value = speed; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 11 , bytes); + + // Status and Error Code + value = status; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 12 , bytes); + + // Second RPM without Offset + value = secondrpm / 100; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 13 , bytes); + +} + + +void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes) +{ + if(slotId > 0 && slotId < SBUS2_SLOT_COUNT) { + sbusTelemetryData[slotId].payload.data[0] = bytes[0]; + sbusTelemetryData[slotId].payload.data[1] = bytes[1]; + sbusTelemetryData[slotId].slotId = sbus2SlotIds[slotId]; + //sbusTelemetryData[i].payload.data[0] = 0x81; + //sbusTelemetryData[i].payload.data[1] = 0x80; + sbusTelemetryDataUsed[slotId] = 1; + } + +} + #endif diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 9fdbc3fd7db..62dcd85aecf 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -22,89 +22,35 @@ #include "platform.h" +#include "common/time.h" + #define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 #define SBUS2_TELEMETRY_ITEM_SIZE 3 #define SBUS2_TELEMETRY_SLOTS 8 #define SBUS2_TELEMETRY_PAGES 4 +#define SBUS2_DEADTIME MS2US(2) +#define SBUS2_SLOT_TIME 700 +#define SBUS2_SLOT_DELAY_MAX 200 + #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) -#if defined(USE_TELEMETRY) && defined(USE_SBUS2_TELEMETRY) +#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) // Information on SBUS2 sensors from: https://github.com/BrushlessPower/SBUS2-Telemetry/tree/master -// Temperature: -// Max 125C -// value | 0x4000 -typedef struct sbus2_telemetry_temp_payload_s { - uint8_t tempHigh; // temp | 0x4000; // 125c - uint8_t tempLow; -} __attribute__((packed)) sbsu2_telemetry_temp_payload_t; - -// Temperature: -// Max 200C -// temp | 0x8000 -typedef struct sbus2_telemetry_temp200_payload_s { - uint8_t tempLow; // temp | 0x8000; // 200c - uint8_t tempHigh; -} __attribute__((packed)) sbsu2_telemetry_temp200_payload_t; - -// RPM: -// (RPM / 6) max: 0xFFFF -typedef struct sbus2_telemetry_rpm_payload_s { - uint8_t rpmHigh; // RPM / 6, capped at 0xFFFF - uint8_t rpmLow; -} __attribute__((packed)) sbsu2_telemetry_rpm_payload_t; - -// Voltage: 1 or 2 slots -// 0x8000 = rx voltage? -// max input: 0x1FFF -typedef struct sbus2_telemetry_voltage_payload_s { - uint8_t voltageHigh; // 2 slots // Voltage 1: value | 0x8000 - uint8_t voltageLow; // max input value: 0x1FFF -} __attribute__((packed)) sbsu2_telemetry_voltage_payload_t; - -// Current -// 3 frames -// 1: current -// Max input: 0x3FFF -// input |= 0x4000 -// input &= 0x7FFF -// 2: voltage -// same as voltage frame. may not need ot be capped. -// 3: Capacity -typedef struct sbus2_telemetry_current_payload_s { - uint8_t currentHigh; - uint8_t currentLow; -} __attribute__((packed)) sbsu2_telemetry_current_payload_t; - -typedef struct sbus2_telemetry_capacity_payload_s { - uint8_t capacityHigh; - uint8_t capacityLow; -} __attribute__((packed)) sbsu2_telemetry_capacity_payload_t; - -// GPS -// frames: -// 1: Speed -// 2: Altitude -// 3: Vario -// 4,5: LAT -// 5,6: LON - typedef struct sbus2_telemetry_frame_s { uint8_t slotId; union { uint8_t data[2]; - sbsu2_telemetry_temp_payload_t temp125; - sbsu2_telemetry_temp200_payload_t temp200; - sbsu2_telemetry_rpm_payload_t rpm; - sbsu2_telemetry_voltage_payload_t voltage; - sbsu2_telemetry_current_payload_t current; - sbsu2_telemetry_capacity_payload_t capacity; + uint16_t u16; } payload; } __attribute__((packed)) sbus2_telemetry_frame_t; + +STATIC_ASSERT(sizeof(sbus2_telemetry_frame_t) == 3, sbus2_telemetry_size); + extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT]; extern uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT]; @@ -115,4 +61,101 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs); // time critical, send sbus2 data void taskSendSbus2Telemetry(timeUs_t currentTimeUs); + +uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed); + +// Sensor code from https://github.com/BrushlessPower/SBUS2-Telemetry +// SBUS2 telemetry: 2ms deadtime after rc package +// One new slot every 700us + +/* + * ++++++++++++++++++++++++++++++++ + * Temperature Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_temp125(uint8_t port, int16_t temp); +void send_alarm_as_temp125(uint8_t port, int16_t alarm); +void send_SBS01TE(uint8_t port, int16_t temp); +void send_SBS01T(uint8_t port, int16_t temp); +void send_F1713(uint8_t port, int16_t temp); + +/* + * ++++++++++++++++++++++++++++++++ + * RPM Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_RPM(uint8_t port, uint32_t RPM); +void send_SBS01RB(uint8_t port, uint32_t RPM); +void send_SBS01RM(uint8_t port, uint32_t RPM); +void send_SBS01RO(uint8_t port, uint32_t RPM); +void send_SBS01R(uint8_t port, uint32_t RPM); + +/* + * ++++++++++++++++++++++++++++++++ + * Voltage/Current Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2); +void send_voltagef(uint8_t port,float voltage1, float voltage2); +void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage); +void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage); +void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage); +void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2); +void send_SBS01Vf(uint8_t port,float voltage1, float voltage2); + + +/* + * ++++++++++++++++++++++++++++++++ + * Vario Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario); +void send_f1712_variof(uint8_t port, int16_t altitude, float vario); +void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario); +void send_f1672_variof(uint8_t port, int16_t altitude, float vario); +void send_F1712(uint8_t port, int16_t altitude, int16_t vario); +void send_F1712f(uint8_t port, int16_t altitude, float vario); +void send_F1672(uint8_t port, int16_t altitude, int16_t vario); +void send_F1672f(uint8_t port, int16_t altitude, float vario); + +/* + * ++++++++++++++++++++++++++++++++ + * GPS Sensors + * Note the different Input Types! + * Example: + * Position Berlin Fernsehturm + * https://www.koordinaten-umrechner.de/decimal/52.520832,13.409430?karte=OpenStreetMap&zoom=19 + * Degree Minutes 52° 31.2499 and 13° 24.5658 + * Decimal Degree 52.520832 and 13.409430 + * ++++++++++++++++++++++++++++++++ + */ +// Degree Minutes as Integer -> 52312499 +void send_f1675_gps(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); +// Degree Minutes as Integer -> 52 and 312499 +void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min); +// Degree Minutes as Float -> 52 and 31.2499 +void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min); +// Decimal Degrees as Float -> 52.520832 +void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude); +// Decimal Degrees as Integer -> 52520832 +void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); +void send_SBS10G(uint8_t port, uint16_t hours, uint16_t minutes, uint16_t seconds, float latitude, float longitude, float altitudeMeters, uint16_t speed, float gpsVario); + +/* + * ++++++++++++++++++++++++++++++++ + * ESC Sensors + * Note These sensors only exists on the newer Futaba Radios 18SZ, 16IZ, etc + * ++++++++++++++++++++++++++++++++ + */ + +void send_kontronik(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); +void send_scorpion(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); + +void send_jetcat(uint8_t port, uint32_t rpm, uint16_t egt, uint16_t pump_volt, uint32_t setrpm, uint16_t thrust, uint16_t fuel, uint16_t fuelflow, uint16_t altitude, uint16_t quality, uint16_t volt, uint16_t current, uint16_t speed, uint16_t status, uint32_t secondrpm); + +void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes); + #endif diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index dd6e08961e0..f6ba7f85437 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -23,6 +23,8 @@ #ifdef USE_TELEMETRY +#include "build/debug.h" + #include "common/utils.h" #include "config/parameter_group.h" @@ -49,6 +51,7 @@ #include "telemetry/ibus.h" #include "telemetry/crsf.h" #include "telemetry/srxl.h" +#include "telemetry/sbus2.h" #include "telemetry/sim.h" #include "telemetry/ghst.h" @@ -246,8 +249,9 @@ void telemetryProcess(timeUs_t currentTimeUs) handleGhstTelemetry(currentTimeUs); #endif -#ifdef USE_TELMETRY_SBUS2 +#ifdef USE_TELEMETRY_SBUS2 handleSbus2Telemetry(currentTimeUs); + DEBUG_SET(DEBUG_SBUS2, 7, 1); #endif } From 92d6315e59446cda53422ea9c08d06fe6f19a0dd Mon Sep 17 00:00:00 2001 From: MUSTARDTIGERFPV Date: Thu, 11 Jul 2024 20:19:47 +0000 Subject: [PATCH 102/212] Improve MAVLink behavior with half-duplex links, update default SRs --- docs/Settings.md | 4 ++-- src/main/fc/settings.yaml | 4 ++-- src/main/telemetry/mavlink.c | 19 ++++++++++++------- 3 files changed, 16 insertions(+), 11 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index a217a26a981..393960c2622 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2518,7 +2518,7 @@ Rate of the extra1 message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | -| 10 | 0 | 255 | +| 2 | 0 | 255 | --- @@ -2558,7 +2558,7 @@ Rate of the RC channels message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 255 | +| 1 | 0 | 255 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 6670148d0bd..5caf1dd8215 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3155,7 +3155,7 @@ groups: type: uint8_t min: 0 max: 255 - default_value: 5 + default_value: 1 - name: mavlink_pos_rate description: "Rate of the position message for MAVLink telemetry" field: mavlink.position_rate @@ -3169,7 +3169,7 @@ groups: type: uint8_t min: 0 max: 255 - default_value: 10 + default_value: 2 - name: mavlink_extra2_rate description: "Rate of the extra2 message for MAVLink telemetry" field: mavlink.extra2_rate diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index be10ad1fd95..8931ed83c83 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1222,6 +1222,11 @@ static bool processMAVLinkIncomingTelemetry(void) return false; } +static bool isMAVLinkTelemetryHalfDuplex(void) { + return telemetryConfig()->halfDuplex || + (rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_MAVLINK && tristateWithDefaultOffIsActive(rxConfig()->halfDuplex)); +} + void handleMAVLinkTelemetry(timeUs_t currentTimeUs) { if (!mavlinkTelemetryEnabled) { @@ -1232,18 +1237,18 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs) return; } - // Process incoming MAVLink - ignore the return indicating whether or not a message was processed - // Very few telemetry links are dynamic uplink/downlink split so uplink telemetry shouldn't reduce downlink bandwidth availability - processMAVLinkIncomingTelemetry(); - - // Determine whether to send telemetry back + // Process incoming MAVLink + bool receivedMessage = processMAVLinkIncomingTelemetry(); bool shouldSendTelemetry = false; + + // Determine whether to send telemetry back based on flow control / pacing if (txbuff_valid) { // Use flow control if available shouldSendTelemetry = txbuff_free >= 33; } else { - // If not, use blind frame pacing - shouldSendTelemetry = (currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY; + // If not, use blind frame pacing - and back off for collision avoidance if half-duplex + bool halfDuplexBackoff = (isMAVLinkTelemetryHalfDuplex() && receivedMessage); + shouldSendTelemetry = ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff; } if (shouldSendTelemetry) { From e8ba7a43ac7ceeffe28d48945e7e35655821f113 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 11 Jul 2024 23:36:50 +0200 Subject: [PATCH 103/212] somewhat works. slow inconsisten updates --- src/main/telemetry/sbus2.c | 73 ++++++++++++++++++++++++++++---------- src/main/telemetry/sbus2.h | 2 +- 2 files changed, 55 insertions(+), 20 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 5cb6e40f276..716e850c521 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -23,12 +23,23 @@ #include "common/utils.h" #include "common/time.h" +#include "common/axis.h" #include "telemetry/telemetry.h" #include "telemetry/sbus2.h" #include "rx/sbus.h" +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "navigation/navigation.h" + +#ifdef USE_ESC_SENSOR +#include "sensors/esc_sensor.h" +#include "flight/mixer.h" +#endif + #ifdef USE_TELEMETRY_SBUS2 const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { @@ -48,16 +59,50 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); - // TODO: placeholder - - for (int i = 1; i < SBUS2_SLOT_COUNT; ++i) { - int16_t temp = 41 + i; - send_SBS01T(i, temp); + float voltage = getBatteryVoltage() * 0.01f; + float cellVoltage = getBatteryAverageCellVoltage() * 0.01f; + float current = getAmperage() * 0.01f; + float capacity = getMAhDrawn(); + float altitude = getEstimatedActualPosition(Z) * 0.01f; + float vario = getEstimatedActualVelocity(Z); + float temperature = 0; + uint32_t rpm = 0; + +#ifdef USE_ESC_SENSOR + escSensorData_t * escSensor = escSensorGetData(); + if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { + rpm = escSensor->rpm; + temperature = escSensor->temperature; + } else { + rpm = 0; + temperature = 0; } +#endif - DEBUG_SET(DEBUG_SBUS2, 5, 42); -} + temperature = 42.16f; + + DEBUG_SET(DEBUG_SBUS2, 0, voltage); + DEBUG_SET(DEBUG_SBUS2, 1, cellVoltage); + DEBUG_SET(DEBUG_SBUS2, 2, current); + DEBUG_SET(DEBUG_SBUS2, 3, capacity); + DEBUG_SET(DEBUG_SBUS2, 4, altitude); + DEBUG_SET(DEBUG_SBUS2, 5, vario); + DEBUG_SET(DEBUG_SBUS2, 6, rpm); + DEBUG_SET(DEBUG_SBUS2, 7, temperature); + + // 2 slots + send_voltagef(1, voltage, cellVoltage); + // 3 slots + send_s1678_currentf(3, current, capacity, voltage); + // 1 slot + send_RPM(6, rpm); + // 1 slot - esc temp + //send_temp125(7, temperature); + send_SBS01T(7, temperature); + // 8 slots - gps + // +} #define SBUS2_DEADTIME MS2US(2) #define SBUS2_SLOT_TIME 700 @@ -83,40 +128,31 @@ void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { if (!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || rxConfig()->serialrx_provider != SERIALRX_SBUS2) { - DEBUG_SET(DEBUG_SBUS2, 0, -1); return; } timeUs_t elapsedTime = currentTimeUs - sbusGetLastFrameTime(); if(elapsedTime > MS2US(8)) { - DEBUG_SET(DEBUG_SBUS2, 0, -2); return; } - DEBUG_SET(DEBUG_SBUS2, 0, 1); uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); uint8_t slot = sbus2GetTelemetrySlot(elapsedTime); if(slot < SBUS2_TELEMETRY_SLOTS) { - DEBUG_SET(DEBUG_SBUS2, 1, telemetryPage); - DEBUG_SET(DEBUG_SBUS2, 2, slot); - DEBUG_SET(DEBUG_SBUS2, 4, -1); int slotIndex = (telemetryPage * SBUS2_TELEMETRY_SLOTS) + slot; if (slotIndex < SBUS2_SLOT_COUNT) { - DEBUG_SET(DEBUG_SBUS2, 3, slotIndex); if (sbusTelemetryDataUsed[slotIndex] != 0 && sbusTelemetryMinDelay[slotIndex] < currentTimeUs) { sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; // send serialWriteBuf(telemetrySharedPort, (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); - sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(2); + sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(1); sbusTelemetryDataUsed[slotIndex] = 0; - - DEBUG_SET(DEBUG_SBUS2, 4, slotIndex); } } } @@ -156,10 +192,9 @@ void send_SBS01T(uint8_t port, int16_t temp){ value = value + 100; bytes[0] = value;// >> 8; bytes[1] = value >> 8; - SBUS2_transmit_telemetry_data( port , bytes); + SBUS2_transmit_telemetry_data(port , bytes); } - void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2) { uint16_t value = 0; diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 62dcd85aecf..d6683a4dc53 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -32,7 +32,7 @@ #define SBUS2_DEADTIME MS2US(2) #define SBUS2_SLOT_TIME 700 -#define SBUS2_SLOT_DELAY_MAX 200 +#define SBUS2_SLOT_DELAY_MAX 300 #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) From 935d309e1363c3c6a64f80fa1c280ebeac107bf2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 00:12:54 +0200 Subject: [PATCH 104/212] Fix build --- src/main/rx/sbus.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index e8f67522b77..9c0fa30bd11 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -77,7 +77,6 @@ static void sbusDataReceive(uint16_t c, void *data) const timeUs_t currentTimeUs = micros(); const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs); sbusFrameData->lastActivityTimeUs = currentTimeUs; - bool isSbus2Frame = true; // Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { @@ -110,7 +109,6 @@ static void sbusDataReceive(uint16_t c, void *data) if(frame->endByte & 0x4) { sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF; frameTime = currentTimeUs; - isSbus2Frame = true; } else { sbus2ActiveTelemetryPage = 0; sbus2ActiveTelemetrySlot = 0; From 248144d17f05f88868cdd95c04245277d0a0774c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 00:15:44 +0200 Subject: [PATCH 105/212] more fixes --- src/main/telemetry/sbus2.c | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 716e850c521..64a6bd46c49 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -104,9 +104,6 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) // } -#define SBUS2_DEADTIME MS2US(2) -#define SBUS2_SLOT_TIME 700 -#define SBUS2_SLOT_DELAY_MAX 200 uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) { if (elapsed < SBUS2_DEADTIME) { From 04f065a180964bb18cee6a1b9c3fbe77112db5bb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 11:54:58 +0200 Subject: [PATCH 106/212] resend stale data --- src/main/telemetry/sbus2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 64a6bd46c49..a8c0c7e83a8 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -149,7 +149,7 @@ void taskSendSbus2Telemetry(timeUs_t currentTimeUs) (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(1); - sbusTelemetryDataUsed[slotIndex] = 0; + //sbusTelemetryDataUsed[slotIndex] = 0; } } } From 49f81af5275f36f209f2299447e3a167bca11cc9 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Fri, 12 Jul 2024 21:35:45 +0800 Subject: [PATCH 107/212] Add blackbox device FILE for SITL build --- src/main/blackbox/blackbox.c | 3 ++ src/main/blackbox/blackbox_io.c | 70 +++++++++++++++++++++++++++++++++ src/main/blackbox/blackbox_io.h | 3 ++ src/main/fc/settings.yaml | 2 +- 4 files changed, 77 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 419b7b4add4..324b41a1095 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1442,6 +1442,9 @@ static void blackboxValidateConfig(void) #endif #ifdef USE_SDCARD case BLACKBOX_DEVICE_SDCARD: +#endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: #endif case BLACKBOX_DEVICE_SERIAL: // Device supported, leave the setting alone diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 3e6adb719b7..dfa79b16eda 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -19,6 +19,11 @@ #include #include +#if defined(SITL_BUILD) +#include +#include +#endif + #include "platform.h" #ifdef USE_BLACKBOX @@ -81,6 +86,12 @@ static struct { #endif +#if defined(SITL_BUILD) +static struct { + FILE *file_handler; +} blackboxFile; +#endif + #ifndef UNIT_TEST void blackboxOpen(void) { @@ -103,6 +114,11 @@ void blackboxWrite(uint8_t value) case BLACKBOX_DEVICE_SDCARD: afatfs_fputc(blackboxSDCard.logFile, value); break; +#endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + fputc(value, blackboxFile.file_handler); + break; #endif case BLACKBOX_DEVICE_SERIAL: default: @@ -133,6 +149,13 @@ int blackboxPrint(const char *s) break; #endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + length = strlen(s); + fputs(s, blackboxFile.file_handler); + break; +#endif + case BLACKBOX_DEVICE_SERIAL: default: pos = (uint8_t*) s; @@ -196,6 +219,12 @@ bool blackboxDeviceFlushForce(void) return afatfs_flush(); #endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + fflush(blackboxFile.file_handler); + return true; +#endif + default: return false; } @@ -271,6 +300,26 @@ bool blackboxDeviceOpen(void) return true; break; #endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + { + const time_t now = time(NULL); + const struct tm *t = localtime(&now); + char filename[32]; + strftime(filename, sizeof(filename), "%Y_%m_%d_%H%M%S.TXT", t); + + blackboxFile.file_handler = fopen(filename, "wb"); + if (blackboxFile.file_handler == NULL) { + fprintf(stderr, "[BlackBox] Failed to create log file\n"); + return false; + } + fprintf(stderr, "[BlackBox] Created %s\n", filename); + } + + blackboxMaxHeaderBytesPerIteration = BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION; + return true; + break; +#endif default: return false; } @@ -302,6 +351,11 @@ void blackboxDeviceClose(void) // Some flash device, e.g., NAND devices, require explicit close to flush internally buffered data. flashfsClose(); break; +#endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + fclose(blackboxFile.file_handler); + break; #endif default: ; @@ -506,6 +560,11 @@ bool isBlackboxDeviceFull(void) return afatfs_isFull(); #endif +#if defined (SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + return false; +#endif + default: return false; } @@ -562,6 +621,11 @@ void blackboxReplenishHeaderBudget(void) case BLACKBOX_DEVICE_SDCARD: freeSpace = afatfs_getFreeBufferSpace(); break; +#endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + freeSpace = BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET; + break; #endif default: freeSpace = 0; @@ -631,6 +695,12 @@ blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes) return BLACKBOX_RESERVE_TEMPORARY_FAILURE; #endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + // Assume that all writes will fit in the file's buffers + return BLACKBOX_RESERVE_TEMPORARY_FAILURE; +#endif + default: return BLACKBOX_RESERVE_PERMANENT_FAILURE; } diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index d143b72098d..76b03b5cd6a 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -31,6 +31,9 @@ typedef enum BlackboxDevice { #ifdef USE_SDCARD BLACKBOX_DEVICE_SDCARD = 2, #endif +#if defined(SITL_BUILD) + BLACKBOX_DEVICE_FILE = 3, +#endif BLACKBOX_DEVICE_END } BlackboxDevice; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 52d6d63f66e..341fe95bddd 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -25,7 +25,7 @@ tables: - name: serial_rx values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK", "FBUS"] - name: blackbox_device - values: ["SERIAL", "SPIFLASH", "SDCARD"] + values: ["SERIAL", "SPIFLASH", "SDCARD", "FILE"] - name: motor_pwm_protocol values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"] - name: servo_protocol From ed4aac11222a3da2ee6c92a36d9faf34d8495ed3 Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Fri, 12 Jul 2024 22:29:36 +0800 Subject: [PATCH 108/212] Set blackbox file handler to NULL after closing file --- src/main/blackbox/blackbox_io.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index dfa79b16eda..36a9750be84 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -355,6 +355,7 @@ void blackboxDeviceClose(void) #if defined(SITL_BUILD) case BLACKBOX_DEVICE_FILE: fclose(blackboxFile.file_handler); + blackboxFile.file_handler = NULL; break; #endif default: From 972dd9f4463dd2196878b9ec70d2d6b833c7e36e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 21:56:11 +0200 Subject: [PATCH 109/212] Add some documentation --- docs/SBUS2_Telemetry.md | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) create mode 100644 docs/SBUS2_Telemetry.md diff --git a/docs/SBUS2_Telemetry.md b/docs/SBUS2_Telemetry.md new file mode 100644 index 00000000000..6a24ea37a88 --- /dev/null +++ b/docs/SBUS2_Telemetry.md @@ -0,0 +1,19 @@ +# Futaba SBUS2 Telemetry + +Basic support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is somewhat unreliable and slow to update. + +The basic sensors have been tested with a Futaba T16IZ running software version 6.0E. + +# Sensor mapping + +The follow fixed sensor mapping is used: +| Slot | Sensort Type | Info | +| --- | --- | --- | +| 1 | Voltage | Pack voltage and cell voltage | +| 3 | Current | Capacity = used mAh | +| 6 | rpm sensor | motor rpm. Need to set geat ratio to 1.0 | +| 7 | Temperature | ESC Temperature | +| 8 | GPS | | +| 16 | Temperature | IMU Temperature | +| 17 | Temperature | Baro Temperature | +| 18-25 | Temperature | Temperature sensor 0-7 | From 0548e6b8aa4bf1e4d18c74f240d40c0948e46078 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 22:34:16 +0200 Subject: [PATCH 110/212] Working a bit more reliably. I am concerned about the realtime priority. Will need to test fly it a bit more to be sure. --- src/main/common/maths.h | 4 ++++ src/main/fc/fc_tasks.c | 4 ++-- src/main/telemetry/sbus2.c | 48 +++++++++++++++++++++++++++++++++++--- src/main/telemetry/sbus2.h | 4 ++-- 4 files changed, 53 insertions(+), 7 deletions(-) diff --git a/src/main/common/maths.h b/src/main/common/maths.h index b8d3803613f..2dbb53c0a1d 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -73,6 +73,10 @@ #define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) #define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) +#define CMSEC_TO_MPH(cms) (CMSEC_TO_CENTIMPH(cms) / 100.0f) +#define CMSEC_TO_KPH(cms) (CMSEC_TO_CENTIKPH(cms) / 100.0f) +#define CMSEC_TO_KNOTS(cms) (CMSEC_TO_CENTIKNOTS(cms) / 100.0f) + #define C_TO_KELVIN(temp) (temp + 273.15f) // Standard Sea Level values diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index b269681baa7..7a456699fa9 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -735,8 +735,8 @@ cfTask_t cfTasks[TASK_COUNT] = { [TASK_TELEMETRY_SBUS2] = { .taskName = "SBUS2_TELEMETRY", .taskFunc = taskSendSbus2Telemetry, - .desiredPeriod = TASK_PERIOD_HZ(2000), - .staticPriority = TASK_PRIORITY_IDLE, + .desiredPeriod = TASK_PERIOD_US(125), // 8kHz 2ms dead time + 650us window / sensor. + .staticPriority = TASK_PRIORITY_REALTIME, // timing is critical. Ideally, should be a timer interrupt triggered by sbus packet }, #endif diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index a8c0c7e83a8..79678df0be9 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -32,6 +32,10 @@ #include "sensors/battery.h" #include "sensors/sensors.h" +#include "sensors/temperature.h" +#include "sensors/diagnostics.h" + +#include "io/gps.h" #include "navigation/navigation.h" @@ -79,7 +83,7 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) } #endif - temperature = 42.16f; + //temperature = 42.16f; DEBUG_SET(DEBUG_SBUS2, 0, voltage); DEBUG_SET(DEBUG_SBUS2, 1, cellVoltage); @@ -97,9 +101,47 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) // 1 slot send_RPM(6, rpm); // 1 slot - esc temp - //send_temp125(7, temperature); + static int change = 0; + change++; + int delta = change / 10; + delta = delta % 20; send_SBS01T(7, temperature); + // 8 slots, gps + uint16_t speed = 0; + float latitude = 0; + float longitude = 0; + +#ifdef USE_GPS + if (gpsSol.fixType >= GPS_FIX_2D) { + speed = (CMSEC_TO_KPH(gpsSol.groundSpeed) + 0.5f); + latitude = gpsSol.llh.lat * 1e-7; + longitude = gpsSol.llh.lon * 1e-7; + } +#endif + + send_F1675f(8, speed, altitude, vario, latitude, longitude); + // imu 1 slot + int16_t temp16; + bool valid = getIMUTemperature(&temp16); + send_SBS01T(16, valid ? temp16 / 10 : 0); + // baro + valid = 0; + valid = getBaroTemperature(&temp16); + send_SBS01T(17, valid ? temp16 / 10 : 0); + // temp sensors 18-25 +#ifdef USE_TEMPERATURE_SENSOR + for(int i = 0; i < 8; i++) { + temp16 = 0; + valid = getSensorTemperature(0, &temp16); + send_SBS01T(18 + i, valid ? temp16 / 10 : 0); + } +#else + for(int i = 0; i < 8; i++) { + send_SBS01T(18 + i, 0); + } +#endif + // 8 slots - gps // } @@ -121,7 +163,7 @@ uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) return slot; } -void taskSendSbus2Telemetry(timeUs_t currentTimeUs) +FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { if (!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || rxConfig()->serialrx_provider != SERIALRX_SBUS2) { diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index d6683a4dc53..675ab8d729d 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -31,8 +31,8 @@ #define SBUS2_TELEMETRY_PAGES 4 #define SBUS2_DEADTIME MS2US(2) -#define SBUS2_SLOT_TIME 700 -#define SBUS2_SLOT_DELAY_MAX 300 +#define SBUS2_SLOT_TIME 650 +#define SBUS2_SLOT_DELAY_MAX 350 #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) From bc008ef72753efafa1e8e618a8e04989621217fb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 22:38:57 +0200 Subject: [PATCH 111/212] Update docs --- docs/SBUS2_Telemetry.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/docs/SBUS2_Telemetry.md b/docs/SBUS2_Telemetry.md index 6a24ea37a88..9fb0c43e4f4 100644 --- a/docs/SBUS2_Telemetry.md +++ b/docs/SBUS2_Telemetry.md @@ -1,9 +1,14 @@ # Futaba SBUS2 Telemetry -Basic support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is somewhat unreliable and slow to update. +Basic experimental support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is limited to F7 and H7 mcus only. The main reason it is limited to those MCUs is due to it requiring an inverted UART signal, and the SBUS pads in F405 usually are not bi-directional. The basic sensors have been tested with a Futaba T16IZ running software version 6.0E. +An alternative to using INAV's SBUS2 support is to use SBS-01ML MAVlink Telemetry Drone Sensor instead. (not tested) + +# Wiring +The SBUS2 signal should be connected to the TX PIN, not the RX PIN, like on a traditional SBUS setup. + # Sensor mapping The follow fixed sensor mapping is used: From cf33eb72ffcae3ba6ff9fcfcc41066ec2658dbf1 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 12 Jul 2024 23:06:26 +0200 Subject: [PATCH 112/212] Small changes --- src/main/telemetry/sbus2.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 675ab8d729d..5787b5c10fd 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -31,8 +31,8 @@ #define SBUS2_TELEMETRY_PAGES 4 #define SBUS2_DEADTIME MS2US(2) -#define SBUS2_SLOT_TIME 650 -#define SBUS2_SLOT_DELAY_MAX 350 +#define SBUS2_SLOT_TIME 650u +#define SBUS2_SLOT_DELAY_MAX (MIN(350u, (SBUS2_SLOT_TIME / 2u))) #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) From 42ae58841f794f5d15e62292f1f2d3423e2745b0 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 13 Jul 2024 01:02:59 +0200 Subject: [PATCH 113/212] Update docs --- docs/SBUS2_Telemetry.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/SBUS2_Telemetry.md b/docs/SBUS2_Telemetry.md index 9fb0c43e4f4..d8a1cd8f1e1 100644 --- a/docs/SBUS2_Telemetry.md +++ b/docs/SBUS2_Telemetry.md @@ -11,7 +11,8 @@ The SBUS2 signal should be connected to the TX PIN, not the RX PIN, like on a tr # Sensor mapping -The follow fixed sensor mapping is used: +The following fixed sensor mapping is used: + | Slot | Sensort Type | Info | | --- | --- | --- | | 1 | Voltage | Pack voltage and cell voltage | From 87356e94fc9cdd98fb2ea7599971418ee87649ed Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 13 Jul 2024 21:38:08 -0500 Subject: [PATCH 114/212] GEPRC_F722_AIO include UART3 --- src/main/target/GEPRC_F722_AIO/target.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h index f7ed46bd466..5dede599778 100644 --- a/src/main/target/GEPRC_F722_AIO/target.h +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -108,6 +108,10 @@ #define UART2_RX_PIN PA3 #define UART2_TX_PIN PA2 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + #define USE_UART4 #define UART4_RX_PIN PC11 #define UART4_TX_PIN PC10 @@ -116,7 +120,7 @@ #define UART5_RX_PIN PD2 #define UART5_TX_PIN PC12 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 6 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS From 934fb4c777f89f752793135f8ffb8c7b3c11f93b Mon Sep 17 00:00:00 2001 From: Bart Slinger Date: Sun, 14 Jul 2024 10:55:36 +0800 Subject: [PATCH 115/212] Blackbox device type 'file' (SITL) considered working when file handler is available --- src/main/blackbox/blackbox_io.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 36a9750be84..b344b0dfff6 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -583,6 +583,10 @@ bool isBlackboxDeviceWorking(void) #ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: return flashfsIsReady(); +#endif +#if defined(SITL_BUILD) + case BLACKBOX_DEVICE_FILE: + return blackboxFile.file_handler != NULL; #endif default: return false; From 6337989e34803198314f5355a5e6c13a625c2b0d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 17 Jul 2024 08:54:52 +0200 Subject: [PATCH 116/212] Add gyros to DakeFPV targets --- src/main/target/DAKEFPVF405/target.h | 5 +++++ src/main/target/DAKEFPVF722/target.h | 15 +++++++++++++++ 2 files changed, 20 insertions(+) diff --git a/src/main/target/DAKEFPVF405/target.h b/src/main/target/DAKEFPVF405/target.h index 41c128668ef..9b1aef0721a 100644 --- a/src/main/target/DAKEFPVF405/target.h +++ b/src/main/target/DAKEFPVF405/target.h @@ -67,6 +67,11 @@ #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PA4 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + //Baro #define USE_BARO #define USE_BARO_BMP280 diff --git a/src/main/target/DAKEFPVF722/target.h b/src/main/target/DAKEFPVF722/target.h index 92cc65783b8..f0f4584e801 100644 --- a/src/main/target/DAKEFPVF722/target.h +++ b/src/main/target/DAKEFPVF722/target.h @@ -57,6 +57,21 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_BUS BUS_SPI1 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW90_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + //Baro #define USE_BARO #define USE_BARO_BMP280 From 0b019a0739df3aa5bbd31f22731df9e702585177 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 18 Jul 2024 12:41:12 +0100 Subject: [PATCH 117/212] Updated Logic Condition constraints to INT32 from INT16 --- src/main/programming/logic_condition.c | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 6e43d2394cd..24eb93d77c6 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -650,15 +650,15 @@ static int logicConditionGetFlightOperandValue(int operand) { switch (operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER: // in s - return constrain((uint32_t)getFlightTime(), 0, INT16_MAX); + return constrain((uint32_t)getFlightTime(), 0, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE: //in m - return constrain(GPS_distanceToHome, 0, INT16_MAX); + return constrain(GPS_distanceToHome, 0, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE: //in m - return constrain(getTotalTravelDistance() / 100, 0, INT16_MAX); + return constrain(getTotalTravelDistance() / 100, 0, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_RSSI: @@ -713,18 +713,18 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED: // cm/s #ifdef USE_PITOT - return constrain(getAirspeedEstimate(), 0, INT16_MAX); + return constrain(getAirspeedEstimate(), 0, INT32_MAX); #else return false; #endif break; case LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE: // cm - return constrain(getEstimatedActualPosition(Z), INT16_MIN, INT16_MAX); + return constrain(getEstimatedActualPosition(Z), INT32_MIN, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED: // cm/s - return constrain(getEstimatedActualVelocity(Z), INT16_MIN, INT16_MAX); + return constrain(getEstimatedActualVelocity(Z), INT32_MIN, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS: // % @@ -793,7 +793,7 @@ static int logicConditionGetFlightOperandValue(int operand) { break; case LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE: //in m - return constrain(calc_length_pythagorean_2D(GPS_distanceToHome, getEstimatedActualPosition(Z) / 100.0f), 0, INT16_MAX); + return constrain(calc_length_pythagorean_2D(GPS_distanceToHome, getEstimatedActualPosition(Z) / 100.0f), 0, INT32_MAX); break; case LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_LQ: From 59f5737e926d19fc7918ac8ea510056287c66b9f Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 18 Jul 2024 12:48:18 +0100 Subject: [PATCH 118/212] Use int32_t explicitly, rather than int --- src/main/programming/logic_condition.c | 14 +++++++------- src/main/programming/logic_condition.h | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 24eb93d77c6..594db21417c 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -513,7 +513,7 @@ static int logicConditionCompute( void logicConditionProcess(uint8_t i) { - const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); + const int32_t activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); if (logicConditions(i)->enabled && activatorValue && !cliMode) { @@ -522,9 +522,9 @@ void logicConditionProcess(uint8_t i) { * Latched LCs can only go from OFF to ON, not the other way */ if (!(logicConditionStates[i].flags & LOGIC_CONDITION_FLAG_LATCH)) { - const int operandAValue = logicConditionGetOperandValue(logicConditions(i)->operandA.type, logicConditions(i)->operandA.value); - const int operandBValue = logicConditionGetOperandValue(logicConditions(i)->operandB.type, logicConditions(i)->operandB.value); - const int newValue = logicConditionCompute( + const int32_t operandAValue = logicConditionGetOperandValue(logicConditions(i)->operandA.type, logicConditions(i)->operandA.value); + const int32_t operandBValue = logicConditionGetOperandValue(logicConditions(i)->operandB.type, logicConditions(i)->operandB.value); + const int32_t newValue = logicConditionCompute( logicConditionStates[i].value, logicConditions(i)->operation, operandAValue, @@ -938,8 +938,8 @@ static int logicConditionGetFlightModeOperandValue(int operand) { } } -int logicConditionGetOperandValue(logicOperandType_e type, int operand) { - int retVal = 0; +int32_t logicConditionGetOperandValue(logicOperandType_e type, int operand) { + int32_t retVal = 0; switch (type) { @@ -994,7 +994,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) { /* * conditionId == -1 is always evaluated as true */ -int logicConditionGetValue(int8_t conditionId) { +int32_t logicConditionGetValue(int8_t conditionId) { if (conditionId >= 0) { return logicConditionStates[conditionId].value; } else { diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 25d6a5a9e1f..74a7765be40 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -249,9 +249,9 @@ extern uint64_t logicConditionsGlobalFlags; void logicConditionProcess(uint8_t i); -int logicConditionGetOperandValue(logicOperandType_e type, int operand); +int32_t logicConditionGetOperandValue(logicOperandType_e type, int operand); -int logicConditionGetValue(int8_t conditionId); +int32_t logicConditionGetValue(int8_t conditionId); void logicConditionUpdateTask(timeUs_t currentTimeUs); void logicConditionReset(void); From 2379a53b2b3789b19fd74e61b4d0ad040e1b4d85 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 18 Jul 2024 17:43:17 +0100 Subject: [PATCH 119/212] Update fc_core.c --- src/main/fc/fc_core.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index da40f9149f5..f7603eee692 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -880,7 +880,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs) cycleTime = getTaskDeltaTime(TASK_SELF); dT = (float)cycleTime * 0.000001f; - if (ARMING_FLAG(ARMED) && (!STATE(FIXED_WING_LEGACY) || !isNavLaunchEnabled() || (isNavLaunchEnabled() && fixedWingLaunchStatus() >= FW_LAUNCH_DETECTED))) { + bool fwLaunchIsActive = STATE(AIRPLANE) && isNavLaunchEnabled() && armTime == 0; + + if (ARMING_FLAG(ARMED) && (!STATE(AIRPLANE) || !fwLaunchIsActive || fixedWingLaunchStatus() >= FW_LAUNCH_DETECTED)) { flightTime += cycleTime; armTime += cycleTime; updateAccExtremes(); From 4e07f771336ee9d125448cfa18b2a3dfa0b77fa6 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 18 Jul 2024 23:35:30 +0200 Subject: [PATCH 120/212] Move things around, in the correct branch --- src/main/CMakeLists.txt | 2 + src/main/telemetry/sbus2.c | 709 +--------------------------- src/main/telemetry/sbus2.h | 97 +--- src/main/telemetry/sbus2_sensors.c | 729 +++++++++++++++++++++++++++++ src/main/telemetry/sbus2_sensors.h | 118 +++++ 5 files changed, 852 insertions(+), 803 deletions(-) create mode 100644 src/main/telemetry/sbus2_sensors.c create mode 100644 src/main/telemetry/sbus2_sensors.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 505512357cc..b6ff0e10985 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -614,6 +614,8 @@ main_sources(COMMON_SRC telemetry/msp_shared.h telemetry/sbus2.c telemetry/sbus2.h + telemetry/sbus2_sensors.c + telemetry/sbus2_sensors.h telemetry/smartport.c telemetry/smartport.h telemetry/sim.c diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 79678df0be9..bcdc1368168 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -27,6 +27,7 @@ #include "telemetry/telemetry.h" #include "telemetry/sbus2.h" +#include "telemetry/sbus2_sensors.h" #include "rx/sbus.h" @@ -197,715 +198,7 @@ FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) } } -// -void send_RPM(uint8_t port, uint32_t RPM) -{ - uint32_t value = 0; - uint8_t bytes[2] = { }; - - value = RPM / 6; - if(value > 0xffff){ - value = 0xffff; - } - bytes[1] = value >> 8; - bytes[0] = value; - SBUS2_transmit_telemetry_data( port , bytes); -} - - -void send_temp125(uint8_t port, int16_t temp) -{ - int16_t value= 0; - uint8_t bytes[2] = { }; - - value = temp | 0x4000; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); -} -void send_SBS01T(uint8_t port, int16_t temp){ - int16_t value= 0; - uint8_t bytes[2] = {}; - - value = temp | 0x8000; - value = value + 100; - bytes[0] = value;// >> 8; - bytes[1] = value >> 8; - SBUS2_transmit_telemetry_data(port , bytes); -} - -void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2) -{ - uint16_t value = 0; - uint8_t bytes[2] = { }; - - // VOLTAGE1 - value = voltage1 | 0x8000; - if ( value > 0x9FFF ){ - value = 0x9FFF; // max voltage is 819.1 - } - else if(value < 0x8000){ - value = 0x8000; - } - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); - - //VOLTAGE2 - value = voltage2; - if ( value > 0x1FFF ){ - value = 0x1FFF; // max voltage is 819.1 - } - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port+1 , bytes); -} - -void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage) -{ - uint16_t value = 0; - uint32_t local = 0; - uint8_t bytes[2] = { }; - - - // CURRENT - local = ((uint32_t)current) * 1 ; - value = (uint16_t)local; - if ( value > 0x3FFF ) - { - // max current is 163.83 - value = 0x3FFF; - } - bytes[0] = value >> 8; - bytes[0] = bytes[0] | 0x40; - bytes[0] = bytes[0] & 0x7F; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); - - //VOLTAGE - local = ((uint32_t)voltage) * 1; - value = (uint16_t)local; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port+1 , bytes); - - // CAPACITY - local = (uint32_t)capacity; - value = (uint16_t)local; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port+2 , bytes); -} - -void send_f1675_gps(uint8_t port, uint16_t speed, int16_t altitude, int16_t vario, int32_t latitude, int32_t longitude) -{ - uint16_t value1 = 0; - int16_t value2 = 0; - uint32_t value3 = 0; - bool latitude_pos = false; - bool longitude_pos = false; - uint8_t bytes[2] = {}; - - - // SPEED -> Bit 14(bytes[1] bit7) -> GPS Valid or not - value1 = speed | 0x4000; - if (value1 > 0x43E7 ){ - value1 = 0x43E7; // max Speed is 999 km/h - } - else if( value1 < 0x4000){ - value1 = 0x4000; - } - bytes[0] = value1 >> 8; - bytes[1] = value1; - SBUS2_transmit_telemetry_data( port , bytes); - - //HIGHT - value2 = altitude | 0x4000; - /*if(value2 > 0x7FFF ){ // max = +16383 - value2 = 0x7FFF; - } - else if( value2 < 0xC000){ // min = -16384 - value2 = 0xC000; - }*/ - bytes[0] = value2 >> 8; - bytes[1] = value2; - SBUS2_transmit_telemetry_data( port+1 , bytes); - - //TIME -> 12:34:56 Uhr = 12*60*60 + 34*60 + 56 = 45296 = 0xB0F0 - bytes[0] = 0xB0; - bytes[1] = 0xF0; - SBUS2_transmit_telemetry_data( port+2 , bytes); - - // VARIO - value2 = vario * 10; - bytes[0] = value2 >> 8; - bytes[1] = value2; - SBUS2_transmit_telemetry_data( port+3 , bytes); - - // LATITUDE - if(latitude >= 0){ - latitude_pos = true; - } - else{ - latitude_pos = false; - latitude = latitude * -1; - } - bytes[0] = (uint8_t)(latitude/1000000); - value3 = (uint32_t)(latitude%1000000); - if(latitude_pos){ - bytes[1] = ((value3 >> 16) & 0x0f); // North - } - else{ - bytes[1] = ((value3 >> 16) | 0x1f); // South - } - SBUS2_transmit_telemetry_data( port+4 , bytes); - - bytes[0] = ((value3 >> 8) & 0xff); - bytes[1] = value3 & 0xff; - SBUS2_transmit_telemetry_data( port+5 , bytes); - - // LONGITUDE - if(longitude >= 0){ - longitude_pos = true; - } - else{ - longitude_pos = false; - longitude = longitude * -1; - } - bytes[0] = (uint8_t)(longitude/1000000); - value3 = (uint32_t)(longitude%1000000); - if(longitude_pos){ - bytes[1] = ((value3 >> 16) & 0x0f); // Eath - } - else{ - bytes[1] = ((value3 >> 16) | 0x1f); // West - } - SBUS2_transmit_telemetry_data( port+6 , bytes); - - bytes[0] = ((value3 >> 8) & 0xff); - bytes[1] = value3 & 0xff; - SBUS2_transmit_telemetry_data( port+7 , bytes); -} - -void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario) -{ - int16_t value = 0; - uint8_t bytes[2] = { }; - - // VARIO - value = vario; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port, bytes); - - //HIGHT - value = altitude | 0x4000; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 1, bytes); -} - -void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario) -{ - int16_t value = 0; - uint8_t bytes[2] = { }; - - // VARIO - value = vario; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); - - //HIGHT - value = altitude | 0x4000; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 1 , bytes); - -} - - -void send_SBS01TE(uint8_t port, int16_t temp){ - send_temp125(port, temp); -} -void send_F1713(uint8_t port, int16_t temp){ - send_temp125(port, temp); -} - -void send_SBS01RB(uint8_t port, uint32_t RPM){ - send_RPM(port, RPM); -} -void send_SBS01RM(uint8_t port, uint32_t RPM){ - send_RPM(port, RPM); -} -void send_SBS01RO(uint8_t port, uint32_t RPM){ - send_RPM(port, RPM); -} -void send_SBS01R(uint8_t port, uint32_t RPM){ - send_RPM(port, RPM); -} - -void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ - send_s1678_current(port, current, capacity, voltage); -} -void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage){ - send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); -} -void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage){ - send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); -} -void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2){ - send_voltage(port, voltage1, voltage2); -} -void send_SBS01Vf(uint8_t port,float voltage1, float voltage2){ - send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); -} -void send_voltagef(uint8_t port,float voltage1, float voltage2){ - send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); -} -void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ - send_s1678_current(port, current, capacity, voltage); -} -void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage){ - send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); -} -void send_f1712_variof(uint8_t port, int16_t altitude, float vario){ - send_f1712_vario(port, altitude, (int16_t)(vario * 10)); -} -void send_f1672_variof(uint8_t port, int16_t altitude, float vario){ - send_f1672_vario(port, altitude, (int16_t)(vario * 100)); -} -void send_F1712(uint8_t port, int16_t altitude, int16_t vario){ - send_f1712_vario(port, altitude, vario); -} -void send_F1712f(uint8_t port, int16_t altitude, float vario){ - send_f1712_vario(port, altitude, (int16_t)(vario * 10)); -} -void send_F1672(uint8_t port, int16_t altitude, int16_t vario){ - send_f1672_vario(port, altitude, vario); -} -void send_F1672f(uint8_t port, int16_t altitude, float vario){ - send_f1672_vario(port, altitude, (int16_t)(vario * 100)); -} -void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min){ - bool Lat_Negative = false; - bool Lon_Negative = false; - if(lat_deg < 0){ - Lat_Negative = true; - lat_deg = lat_deg * -1; - } - if(lon_deg < 0){ - Lon_Negative = true; - lon_deg = lon_deg * -1; - } - if(lat_min < 0){ - Lat_Negative = true; - lat_min = lat_min * -1; - } - if(lon_min < 0){ - Lon_Negative = true; - lon_min = lon_min * -1; - } - int32_t _latitude_deg = lat_deg; - int32_t _longitude_deg = lon_deg; - int32_t _latitude_min = lat_min * 10000; - int32_t _longitude_min = lon_min * 10000; - int32_t _latitude = _latitude_deg * 1000000; - int32_t _longitude = _longitude_deg * 1000000; - _latitude = _latitude + _latitude_min; - _longitude = _longitude + _longitude_min; - if(Lat_Negative){ - _latitude = _latitude * -1; - } - if(Lon_Negative){ - _longitude = _longitude * -1; - } - send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); -} -void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min){ - bool Lat_Negative = false; - bool Lon_Negative = false; - if(lat_deg < 0){ - Lat_Negative = true; - lat_deg = lat_deg * -1; - } - if(lon_deg < 0){ - Lon_Negative = true; - lon_deg = lon_deg * -1; - } - if(lat_min < 0){ - Lat_Negative = true; - lat_min = lat_min * -1; - } - if(lon_min < 0){ - Lon_Negative = true; - lon_min = lon_min * -1; - } - int32_t _latitude_deg = lat_deg; - int32_t _longitude_deg = lon_deg; - int32_t _latitude = _latitude_deg * 1000000; - int32_t _longitude = _longitude_deg * 1000000; - _latitude = _latitude + lat_min; - _longitude = _longitude + lon_min; - if(Lat_Negative){ - _latitude = _latitude * -1; - } - if(Lon_Negative){ - _longitude = _longitude * -1; - } - send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); -} -void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude){ - int32_t _latitude = latitude; - int32_t _longitude = longitude; - int32_t _latitude_deg = _latitude/1000000; - int32_t _longitude_deg = _longitude/1000000; - int32_t _latitude_min = _latitude%1000000; - int32_t _longitude_min = _longitude%1000000; - _latitude = _latitude_deg * 1000000; - _longitude = _longitude_deg * 1000000; - _latitude = _latitude + ((_latitude_min * 60)/100); - _longitude = _longitude + ((_longitude_min * 60)/100); - send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); -} -void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude){ - int32_t _latitude = latitude * 1000000; - int32_t _longitude = longitude * 1000000; - int32_t _latitude_deg = _latitude/1000000; - int32_t _longitude_deg = _longitude/1000000; - int32_t _latitude_min = _latitude%1000000; - int32_t _longitude_min = _longitude%1000000; - _latitude = _latitude_deg * 1000000; - _longitude = _longitude_deg * 1000000; - _latitude = _latitude + ((_latitude_min * 60)/100); - _longitude = _longitude + ((_longitude_min * 60)/100); - send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); -} -void send_SBS10G( - uint8_t port, - uint16_t hours, // 0 to 24 - uint16_t minutes, // 0 to 60 - uint16_t seconds, // 0 to 60 - float latitude, // decimal degrees (i.e. 52.520833; negative value for southern hemisphere) - float longitude, // decimal degrees (i.e. 13.409430; negative value for western hemisphere) - float altitudeMeters, // meters (valid range: -1050 to 4600) - uint16_t speed, // km/h (valid range 0 to 511) - float gpsVario) // m/s (valid range: -150 to 260) -{ - uint32_t utc = (hours*3600) + (minutes*60) + seconds; - uint32_t lat, lon; - // scale latitude/longitude (add 0.5 for correct rounding) - if (latitude > 0) { - lat = (600000.0*latitude) + 0.5; - } - else { - lat = (-600000.0*latitude) + 0.5; - // toggle south bit - lat |= 0x4000000; - } - if (longitude > 0) { - lon = (600000.0*longitude) + 0.5; - } - else { - lon = (-600000.0*longitude) + 0.5; - // toggle west bit - lon |= 0x8000000; - } - // convert altitude (add 0.5 for correct rounding) - uint16_t alt = (altitudeMeters>=-820 && altitudeMeters<=4830) ?(1.25*(altitudeMeters+820)) + 0.5 : 0; - // error check speed - if (speed < 512) { - // set speed enable bit - speed |= 0x200; - } - else { - speed = 0; - } - // initialize buffer - uint8_t bytes[2] = { }; - // slot 0 (utc) - bytes[0] = (utc&0x00ff); - bytes[1] = (utc&0xff00)>>8; - SBUS2_transmit_telemetry_data(port , bytes); - // slot 1 (latitude & utc) - bytes[0] = ((lat&0x007f)<<1) | ((utc&0x10000)>>16); - bytes[1] = (lat&0x7f80)>>7; - SBUS2_transmit_telemetry_data(port+1 , bytes); - // slot 2 (latitude & longitude) - bytes[0] = (lat&0x07f8000)>>15; - bytes[1] = ((lat&0x7800000)>>23) | (lon&0x0f)<<4; - SBUS2_transmit_telemetry_data(port+2 , bytes); - // slot 3 (longitude) - bytes[0] = (lon&0x00ff0)>>4; - bytes[1] = (lon&0xff000)>>12; - SBUS2_transmit_telemetry_data(port+3 , bytes); - // slot 4 (longitude & speed) - bytes[0] = ((lon&0xff00000)>>20); - bytes[1] = (speed&0xff); - SBUS2_transmit_telemetry_data(port+4 , bytes); - // slot 5 (pressure & speed) - bytes[0] = ((speed&0x300)>>8); - bytes[1] = 0x00; - SBUS2_transmit_telemetry_data(port+5 , bytes); - // slot 6 (altitude & pressure) - bytes[0] = ((alt&0x003)<<6); - bytes[1] = (alt&0x3fc)>>2; - SBUS2_transmit_telemetry_data(port+6 , bytes); - // slot (7 (vario & altitude) - uint16_t vario; - // error check vario - if (gpsVario >= -150 && gpsVario <= 260) { - // scale vario (add 0.5 for correct rounding) - vario = (10.0*(gpsVario + 150)) + 0.5; - // set vario enable - vario |= 0x1000; - } - else { - vario = 0; - } - bytes[0] = ((vario&0x001f)<<3) | ((alt&0x1c00)>>10); - bytes[1] = (vario&0x1fe0)>>5; - SBUS2_transmit_telemetry_data(port+7 , bytes); -} -void send_scorpion_kontronik( - uint8_t port, - uint16_t voltage, - uint16_t capacity, - uint32_t rpm, - uint16_t current, - uint16_t temp, - uint16_t becTemp, - uint16_t becCurrent, - uint16_t pwm) -{ - uint32_t value = 0; - uint8_t bytes[2] = { }; - - // voltage 41.1 = 4110 - value = voltage | 0x8000; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); - - // 1330 mah => 1.33 Ah - value = capacity; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 1 , bytes); - - // 2250 rpm => 2250 - value = rpm / 6; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 2 , bytes); - - // 13310 => 133.1 A - value = current; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 3 , bytes); - - // 41 => 41 Celsius - value = temp; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 4 , bytes); - - // 21 => Bec Celsius - value = becTemp; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 5 , bytes); - - // 650 => 6,5 Bec Current - value = becCurrent; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 6 , bytes); - - // PWM output - value = pwm; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 7 , bytes); -} - -void send_scorpion( - uint8_t port, - uint16_t voltage, - uint16_t capacity, - uint32_t rpm, - uint16_t current, - uint16_t temp, - uint16_t becTemp, - uint16_t becCurrent, - uint16_t pwm) -{ - send_scorpion_kontronik( - port, - voltage, - capacity, - rpm, - current, - temp, - becTemp, - becCurrent, - pwm); -} - -void send_kontronik( - uint8_t port, - uint16_t voltage, - uint16_t capacity, - uint32_t rpm, - uint16_t current, - uint16_t temp, - uint16_t becTemp, - uint16_t becCurrent, - uint16_t pwm) -{ - send_scorpion_kontronik( - port, - voltage, - capacity, - rpm, - current, - temp, - becTemp, - becCurrent, - pwm); -} - -void send_jetcat( - uint8_t port, - uint32_t rpm, - uint16_t egt, - uint16_t pump_volt, - uint32_t setrpm, - uint16_t thrust, - uint16_t fuel, - uint16_t fuelflow, - uint16_t altitude, - uint16_t quality, - uint16_t volt, - uint16_t current, - uint16_t speed, - uint16_t status, - uint32_t secondrpm) -{ - uint32_t value = 0; - uint8_t bytes[2] = {}; - - // Actual RPM with 0x4000 Offset -> why? - value = rpm / 100; - value = value | 0x4000; - if(value > 0xffff){ - value = 0xffff; - } - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port , bytes); - - // EGT Abgastemperatur in °C - value = egt; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 1 , bytes); - - // Pump Voltage 12.34V = 1234 - value = pump_volt; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 2 , bytes); - - // Setpoint RPM without Offset - value = setrpm / 100; - if(value > 0xffff){ - value = 0xffff; - } - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 3 , bytes); - - // Thrust 123.4N = 1234 - value = thrust; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 4 , bytes); - - // Fuel (remain) in ml - value = fuel; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 5 , bytes); - - // Fuel Flow in ml/min - value = fuelflow; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 6 , bytes); - - // Altitude -> without offset? - value = altitude; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 7 , bytes); - - // Fuel Quality in % - value = quality; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 8 , bytes); - - // Voltage 12.34V = 1234 - value = volt; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 9 , bytes); - - // Current 123.4A = 1234 - value = current; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 10 , bytes); - - // Speed in km/h - value = speed; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 11 , bytes); - - // Status and Error Code - value = status; - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 12 , bytes); - - // Second RPM without Offset - value = secondrpm / 100; - if(value > 0xffff){ - value = 0xffff; - } - bytes[0] = value >> 8; - bytes[1] = value; - SBUS2_transmit_telemetry_data( port + 13 , bytes); - -} - - -void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes) -{ - if(slotId > 0 && slotId < SBUS2_SLOT_COUNT) { - sbusTelemetryData[slotId].payload.data[0] = bytes[0]; - sbusTelemetryData[slotId].payload.data[1] = bytes[1]; - sbusTelemetryData[slotId].slotId = sbus2SlotIds[slotId]; - //sbusTelemetryData[i].payload.data[0] = 0x81; - //sbusTelemetryData[i].payload.data[1] = 0x80; - sbusTelemetryDataUsed[slotId] = 1; - } - -} #endif diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 5787b5c10fd..9c2c39ba73e 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -23,6 +23,7 @@ #include "platform.h" #include "common/time.h" +#include "common/utils.h" #define SBUS2_TELEMETRY_PAYLOAD_SIZE 3 @@ -51,7 +52,7 @@ typedef struct sbus2_telemetry_frame_s { STATIC_ASSERT(sizeof(sbus2_telemetry_frame_t) == 3, sbus2_telemetry_size); -extern const uint8_t Slot_ID[SBUS2_SLOT_COUNT]; +extern const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT]; extern uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT]; extern timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT]; @@ -64,98 +65,4 @@ void taskSendSbus2Telemetry(timeUs_t currentTimeUs); uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed); -// Sensor code from https://github.com/BrushlessPower/SBUS2-Telemetry -// SBUS2 telemetry: 2ms deadtime after rc package -// One new slot every 700us - -/* - * ++++++++++++++++++++++++++++++++ - * Temperature Sensors - * ++++++++++++++++++++++++++++++++ - */ -void send_temp125(uint8_t port, int16_t temp); -void send_alarm_as_temp125(uint8_t port, int16_t alarm); -void send_SBS01TE(uint8_t port, int16_t temp); -void send_SBS01T(uint8_t port, int16_t temp); -void send_F1713(uint8_t port, int16_t temp); - -/* - * ++++++++++++++++++++++++++++++++ - * RPM Sensors - * ++++++++++++++++++++++++++++++++ - */ -void send_RPM(uint8_t port, uint32_t RPM); -void send_SBS01RB(uint8_t port, uint32_t RPM); -void send_SBS01RM(uint8_t port, uint32_t RPM); -void send_SBS01RO(uint8_t port, uint32_t RPM); -void send_SBS01R(uint8_t port, uint32_t RPM); - -/* - * ++++++++++++++++++++++++++++++++ - * Voltage/Current Sensors - * ++++++++++++++++++++++++++++++++ - */ -void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2); -void send_voltagef(uint8_t port,float voltage1, float voltage2); -void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); -void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage); -void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); -void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage); -void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); -void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage); -void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2); -void send_SBS01Vf(uint8_t port,float voltage1, float voltage2); - - -/* - * ++++++++++++++++++++++++++++++++ - * Vario Sensors - * ++++++++++++++++++++++++++++++++ - */ -void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario); -void send_f1712_variof(uint8_t port, int16_t altitude, float vario); -void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario); -void send_f1672_variof(uint8_t port, int16_t altitude, float vario); -void send_F1712(uint8_t port, int16_t altitude, int16_t vario); -void send_F1712f(uint8_t port, int16_t altitude, float vario); -void send_F1672(uint8_t port, int16_t altitude, int16_t vario); -void send_F1672f(uint8_t port, int16_t altitude, float vario); - -/* - * ++++++++++++++++++++++++++++++++ - * GPS Sensors - * Note the different Input Types! - * Example: - * Position Berlin Fernsehturm - * https://www.koordinaten-umrechner.de/decimal/52.520832,13.409430?karte=OpenStreetMap&zoom=19 - * Degree Minutes 52° 31.2499 and 13° 24.5658 - * Decimal Degree 52.520832 and 13.409430 - * ++++++++++++++++++++++++++++++++ - */ -// Degree Minutes as Integer -> 52312499 -void send_f1675_gps(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); -// Degree Minutes as Integer -> 52 and 312499 -void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min); -// Degree Minutes as Float -> 52 and 31.2499 -void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min); -// Decimal Degrees as Float -> 52.520832 -void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude); -// Decimal Degrees as Integer -> 52520832 -void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); -void send_SBS10G(uint8_t port, uint16_t hours, uint16_t minutes, uint16_t seconds, float latitude, float longitude, float altitudeMeters, uint16_t speed, float gpsVario); - -/* - * ++++++++++++++++++++++++++++++++ - * ESC Sensors - * Note These sensors only exists on the newer Futaba Radios 18SZ, 16IZ, etc - * ++++++++++++++++++++++++++++++++ - */ - -void send_kontronik(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); -void send_scorpion(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); - -void send_jetcat(uint8_t port, uint32_t rpm, uint16_t egt, uint16_t pump_volt, uint32_t setrpm, uint16_t thrust, uint16_t fuel, uint16_t fuelflow, uint16_t altitude, uint16_t quality, uint16_t volt, uint16_t current, uint16_t speed, uint16_t status, uint32_t secondrpm); - -void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes); - #endif diff --git a/src/main/telemetry/sbus2_sensors.c b/src/main/telemetry/sbus2_sensors.c new file mode 100644 index 00000000000..ec3d05a4bd7 --- /dev/null +++ b/src/main/telemetry/sbus2_sensors.c @@ -0,0 +1,729 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include "telemetry/sbus2.h" +#include "telemetry/sbus2_sensors.h" + +void send_RPM(uint8_t port, uint32_t RPM) +{ + uint32_t value = 0; + uint8_t bytes[2] = { }; + + value = RPM / 6; + if(value > 0xffff){ + value = 0xffff; + } + bytes[1] = value >> 8; + bytes[0] = value; + SBUS2_transmit_telemetry_data( port , bytes); +} + + +void send_temp125(uint8_t port, int16_t temp) +{ + int16_t value= 0; + uint8_t bytes[2] = { }; + + value = temp | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); +} +void send_SBS01T(uint8_t port, int16_t temp){ + int16_t value= 0; + uint8_t bytes[2] = {}; + + value = temp | 0x8000; + value = value + 100; + bytes[0] = value;// >> 8; + bytes[1] = value >> 8; + SBUS2_transmit_telemetry_data(port , bytes); +} + +void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2) +{ + uint16_t value = 0; + uint8_t bytes[2] = { }; + + // VOLTAGE1 + value = voltage1 | 0x8000; + if ( value > 0x9FFF ){ + value = 0x9FFF; // max voltage is 819.1 + } + else if(value < 0x8000){ + value = 0x8000; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //VOLTAGE2 + value = voltage2; + if ( value > 0x1FFF ){ + value = 0x1FFF; // max voltage is 819.1 + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+1 , bytes); +} + +void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage) +{ + uint16_t value = 0; + uint32_t local = 0; + uint8_t bytes[2] = { }; + + + // CURRENT + local = ((uint32_t)current) * 1 ; + value = (uint16_t)local; + if ( value > 0x3FFF ) + { + // max current is 163.83 + value = 0x3FFF; + } + bytes[0] = value >> 8; + bytes[0] = bytes[0] | 0x40; + bytes[0] = bytes[0] & 0x7F; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //VOLTAGE + local = ((uint32_t)voltage) * 1; + value = (uint16_t)local; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+1 , bytes); + + // CAPACITY + local = (uint32_t)capacity; + value = (uint16_t)local; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port+2 , bytes); +} + +void send_f1675_gps(uint8_t port, uint16_t speed, int16_t altitude, int16_t vario, int32_t latitude, int32_t longitude) +{ + uint16_t value1 = 0; + int16_t value2 = 0; + uint32_t value3 = 0; + bool latitude_pos = false; + bool longitude_pos = false; + uint8_t bytes[2] = {}; + + + // SPEED -> Bit 14(bytes[1] bit7) -> GPS Valid or not + value1 = speed | 0x4000; + if (value1 > 0x43E7 ){ + value1 = 0x43E7; // max Speed is 999 km/h + } + else if( value1 < 0x4000){ + value1 = 0x4000; + } + bytes[0] = value1 >> 8; + bytes[1] = value1; + SBUS2_transmit_telemetry_data( port , bytes); + + //HIGHT + value2 = altitude | 0x4000; + /*if(value2 > 0x7FFF ){ // max = +16383 + value2 = 0x7FFF; + } + else if( value2 < 0xC000){ // min = -16384 + value2 = 0xC000; + }*/ + bytes[0] = value2 >> 8; + bytes[1] = value2; + SBUS2_transmit_telemetry_data( port+1 , bytes); + + //TIME -> 12:34:56 Uhr = 12*60*60 + 34*60 + 56 = 45296 = 0xB0F0 + bytes[0] = 0xB0; + bytes[1] = 0xF0; + SBUS2_transmit_telemetry_data( port+2 , bytes); + + // VARIO + value2 = vario * 10; + bytes[0] = value2 >> 8; + bytes[1] = value2; + SBUS2_transmit_telemetry_data( port+3 , bytes); + + // LATITUDE + if(latitude >= 0){ + latitude_pos = true; + } + else{ + latitude_pos = false; + latitude = latitude * -1; + } + bytes[0] = (uint8_t)(latitude/1000000); + value3 = (uint32_t)(latitude%1000000); + if(latitude_pos){ + bytes[1] = ((value3 >> 16) & 0x0f); // North + } + else{ + bytes[1] = ((value3 >> 16) | 0x1f); // South + } + SBUS2_transmit_telemetry_data( port+4 , bytes); + + bytes[0] = ((value3 >> 8) & 0xff); + bytes[1] = value3 & 0xff; + SBUS2_transmit_telemetry_data( port+5 , bytes); + + // LONGITUDE + if(longitude >= 0){ + longitude_pos = true; + } + else{ + longitude_pos = false; + longitude = longitude * -1; + } + bytes[0] = (uint8_t)(longitude/1000000); + value3 = (uint32_t)(longitude%1000000); + if(longitude_pos){ + bytes[1] = ((value3 >> 16) & 0x0f); // Eath + } + else{ + bytes[1] = ((value3 >> 16) | 0x1f); // West + } + SBUS2_transmit_telemetry_data( port+6 , bytes); + + bytes[0] = ((value3 >> 8) & 0xff); + bytes[1] = value3 & 0xff; + SBUS2_transmit_telemetry_data( port+7 , bytes); +} + +void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario) +{ + int16_t value = 0; + uint8_t bytes[2] = { }; + + // VARIO + value = vario; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port, bytes); + + //HIGHT + value = altitude | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1, bytes); +} + +void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario) +{ + int16_t value = 0; + uint8_t bytes[2] = { }; + + // VARIO + value = vario; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + //HIGHT + value = altitude | 0x4000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + +} + + +void send_SBS01TE(uint8_t port, int16_t temp){ + send_temp125(port, temp); +} +void send_F1713(uint8_t port, int16_t temp){ + send_temp125(port, temp); +} + +void send_SBS01RB(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01RM(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01RO(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} +void send_SBS01R(uint8_t port, uint32_t RPM){ + send_RPM(port, RPM); +} + +void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ + send_s1678_current(port, current, capacity, voltage); +} +void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} +void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} +void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2){ + send_voltage(port, voltage1, voltage2); +} +void send_SBS01Vf(uint8_t port,float voltage1, float voltage2){ + send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); +} +void send_voltagef(uint8_t port,float voltage1, float voltage2){ + send_voltage(port, (uint16_t)(voltage1 * 10), (uint16_t)(voltage2 * 10)); +} +void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage){ + send_s1678_current(port, current, capacity, voltage); +} +void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage){ + send_s1678_current(port, (uint16_t)(current * 100), capacity, (uint16_t)(voltage * 100)); +} + +void send_f1712_variof(uint8_t port, int16_t altitude, float vario){ + send_f1712_vario(port, altitude, (int16_t)(vario * 10)); +} +void send_f1672_variof(uint8_t port, int16_t altitude, float vario){ + send_f1672_vario(port, altitude, (int16_t)(vario * 100)); +} +void send_F1712(uint8_t port, int16_t altitude, int16_t vario){ + send_f1712_vario(port, altitude, vario); +} +void send_F1712f(uint8_t port, int16_t altitude, float vario){ + send_f1712_vario(port, altitude, (int16_t)(vario * 10)); +} +void send_F1672(uint8_t port, int16_t altitude, int16_t vario){ + send_f1672_vario(port, altitude, vario); +} +void send_F1672f(uint8_t port, int16_t altitude, float vario){ + send_f1672_vario(port, altitude, (int16_t)(vario * 100)); +} + +void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min){ + bool Lat_Negative = false; + bool Lon_Negative = false; + if(lat_deg < 0){ + Lat_Negative = true; + lat_deg = lat_deg * -1; + } + if(lon_deg < 0){ + Lon_Negative = true; + lon_deg = lon_deg * -1; + } + if(lat_min < 0){ + Lat_Negative = true; + lat_min = lat_min * -1; + } + if(lon_min < 0){ + Lon_Negative = true; + lon_min = lon_min * -1; + } + int32_t _latitude_deg = lat_deg; + int32_t _longitude_deg = lon_deg; + int32_t _latitude_min = lat_min * 10000; + int32_t _longitude_min = lon_min * 10000; + int32_t _latitude = _latitude_deg * 1000000; + int32_t _longitude = _longitude_deg * 1000000; + _latitude = _latitude + _latitude_min; + _longitude = _longitude + _longitude_min; + if(Lat_Negative){ + _latitude = _latitude * -1; + } + if(Lon_Negative){ + _longitude = _longitude * -1; + } + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min){ + bool Lat_Negative = false; + bool Lon_Negative = false; + if(lat_deg < 0){ + Lat_Negative = true; + lat_deg = lat_deg * -1; + } + if(lon_deg < 0){ + Lon_Negative = true; + lon_deg = lon_deg * -1; + } + if(lat_min < 0){ + Lat_Negative = true; + lat_min = lat_min * -1; + } + if(lon_min < 0){ + Lon_Negative = true; + lon_min = lon_min * -1; + } + int32_t _latitude_deg = lat_deg; + int32_t _longitude_deg = lon_deg; + int32_t _latitude = _latitude_deg * 1000000; + int32_t _longitude = _longitude_deg * 1000000; + _latitude = _latitude + lat_min; + _longitude = _longitude + lon_min; + if(Lat_Negative){ + _latitude = _latitude * -1; + } + if(Lon_Negative){ + _longitude = _longitude * -1; + } + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude){ + int32_t _latitude = latitude; + int32_t _longitude = longitude; + int32_t _latitude_deg = _latitude/1000000; + int32_t _longitude_deg = _longitude/1000000; + int32_t _latitude_min = _latitude%1000000; + int32_t _longitude_min = _longitude%1000000; + _latitude = _latitude_deg * 1000000; + _longitude = _longitude_deg * 1000000; + _latitude = _latitude + ((_latitude_min * 60)/100); + _longitude = _longitude + ((_longitude_min * 60)/100); + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude){ + int32_t _latitude = latitude * 1000000; + int32_t _longitude = longitude * 1000000; + int32_t _latitude_deg = _latitude/1000000; + int32_t _longitude_deg = _longitude/1000000; + int32_t _latitude_min = _latitude%1000000; + int32_t _longitude_min = _longitude%1000000; + _latitude = _latitude_deg * 1000000; + _longitude = _longitude_deg * 1000000; + _latitude = _latitude + ((_latitude_min * 60)/100); + _longitude = _longitude + ((_longitude_min * 60)/100); + send_f1675_gps(port, speed, hight, vario, _latitude, _longitude); +} +void send_SBS10G( + uint8_t port, + uint16_t hours, // 0 to 24 + uint16_t minutes, // 0 to 60 + uint16_t seconds, // 0 to 60 + float latitude, // decimal degrees (i.e. 52.520833; negative value for southern hemisphere) + float longitude, // decimal degrees (i.e. 13.409430; negative value for western hemisphere) + float altitudeMeters, // meters (valid range: -1050 to 4600) + uint16_t speed, // km/h (valid range 0 to 511) + float gpsVario) // m/s (valid range: -150 to 260) +{ + uint32_t utc = (hours*3600) + (minutes*60) + seconds; + uint32_t lat, lon; + // scale latitude/longitude (add 0.5 for correct rounding) + if (latitude > 0) { + lat = (600000.0*latitude) + 0.5; + } + else { + lat = (-600000.0*latitude) + 0.5; + // toggle south bit + lat |= 0x4000000; + } + if (longitude > 0) { + lon = (600000.0*longitude) + 0.5; + } + else { + lon = (-600000.0*longitude) + 0.5; + // toggle west bit + lon |= 0x8000000; + } + // convert altitude (add 0.5 for correct rounding) + uint16_t alt = (altitudeMeters>=-820 && altitudeMeters<=4830) ?(1.25*(altitudeMeters+820)) + 0.5 : 0; + // error check speed + if (speed < 512) { + // set speed enable bit + speed |= 0x200; + } + else { + speed = 0; + } + // initialize buffer + uint8_t bytes[2] = { }; + // slot 0 (utc) + bytes[0] = (utc&0x00ff); + bytes[1] = (utc&0xff00)>>8; + SBUS2_transmit_telemetry_data(port , bytes); + // slot 1 (latitude & utc) + bytes[0] = ((lat&0x007f)<<1) | ((utc&0x10000)>>16); + bytes[1] = (lat&0x7f80)>>7; + SBUS2_transmit_telemetry_data(port+1 , bytes); + // slot 2 (latitude & longitude) + bytes[0] = (lat&0x07f8000)>>15; + bytes[1] = ((lat&0x7800000)>>23) | (lon&0x0f)<<4; + SBUS2_transmit_telemetry_data(port+2 , bytes); + // slot 3 (longitude) + bytes[0] = (lon&0x00ff0)>>4; + bytes[1] = (lon&0xff000)>>12; + SBUS2_transmit_telemetry_data(port+3 , bytes); + // slot 4 (longitude & speed) + bytes[0] = ((lon&0xff00000)>>20); + bytes[1] = (speed&0xff); + SBUS2_transmit_telemetry_data(port+4 , bytes); + // slot 5 (pressure & speed) + bytes[0] = ((speed&0x300)>>8); + bytes[1] = 0x00; + SBUS2_transmit_telemetry_data(port+5 , bytes); + // slot 6 (altitude & pressure) + bytes[0] = ((alt&0x003)<<6); + bytes[1] = (alt&0x3fc)>>2; + SBUS2_transmit_telemetry_data(port+6 , bytes); + // slot (7 (vario & altitude) + uint16_t vario; + // error check vario + if (gpsVario >= -150 && gpsVario <= 260) { + // scale vario (add 0.5 for correct rounding) + vario = (10.0*(gpsVario + 150)) + 0.5; + // set vario enable + vario |= 0x1000; + } + else { + vario = 0; + } + bytes[0] = ((vario&0x001f)<<3) | ((alt&0x1c00)>>10); + bytes[1] = (vario&0x1fe0)>>5; + SBUS2_transmit_telemetry_data(port+7 , bytes); +} +void send_scorpion_kontronik( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + uint32_t value = 0; + uint8_t bytes[2] = { }; + + // voltage 41.1 = 4110 + value = voltage | 0x8000; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + // 1330 mah => 1.33 Ah + value = capacity; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + + // 2250 rpm => 2250 + value = rpm / 6; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 2 , bytes); + + // 13310 => 133.1 A + value = current; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 3 , bytes); + + // 41 => 41 Celsius + value = temp; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 4 , bytes); + + // 21 => Bec Celsius + value = becTemp; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 5 , bytes); + + // 650 => 6,5 Bec Current + value = becCurrent; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 6 , bytes); + + // PWM output + value = pwm; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 7 , bytes); +} + +void send_scorpion( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + send_scorpion_kontronik( + port, + voltage, + capacity, + rpm, + current, + temp, + becTemp, + becCurrent, + pwm); +} + +void send_kontronik( + uint8_t port, + uint16_t voltage, + uint16_t capacity, + uint32_t rpm, + uint16_t current, + uint16_t temp, + uint16_t becTemp, + uint16_t becCurrent, + uint16_t pwm) +{ + send_scorpion_kontronik( + port, + voltage, + capacity, + rpm, + current, + temp, + becTemp, + becCurrent, + pwm); +} + +void send_jetcat( + uint8_t port, + uint32_t rpm, + uint16_t egt, + uint16_t pump_volt, + uint32_t setrpm, + uint16_t thrust, + uint16_t fuel, + uint16_t fuelflow, + uint16_t altitude, + uint16_t quality, + uint16_t volt, + uint16_t current, + uint16_t speed, + uint16_t status, + uint32_t secondrpm) +{ + uint32_t value = 0; + uint8_t bytes[2] = {}; + + // Actual RPM with 0x4000 Offset -> why? + value = rpm / 100; + value = value | 0x4000; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port , bytes); + + // EGT Abgastemperatur in °C + value = egt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 1 , bytes); + + // Pump Voltage 12.34V = 1234 + value = pump_volt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 2 , bytes); + + // Setpoint RPM without Offset + value = setrpm / 100; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 3 , bytes); + + // Thrust 123.4N = 1234 + value = thrust; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 4 , bytes); + + // Fuel (remain) in ml + value = fuel; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 5 , bytes); + + // Fuel Flow in ml/min + value = fuelflow; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 6 , bytes); + + // Altitude -> without offset? + value = altitude; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 7 , bytes); + + // Fuel Quality in % + value = quality; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 8 , bytes); + + // Voltage 12.34V = 1234 + value = volt; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 9 , bytes); + + // Current 123.4A = 1234 + value = current; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 10 , bytes); + + // Speed in km/h + value = speed; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 11 , bytes); + + // Status and Error Code + value = status; + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 12 , bytes); + + // Second RPM without Offset + value = secondrpm / 100; + if(value > 0xffff){ + value = 0xffff; + } + bytes[0] = value >> 8; + bytes[1] = value; + SBUS2_transmit_telemetry_data( port + 13 , bytes); + +} + + +void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes) +{ + if(slotId > 0 && slotId < SBUS2_SLOT_COUNT) { + sbusTelemetryData[slotId].payload.data[0] = bytes[0]; + sbusTelemetryData[slotId].payload.data[1] = bytes[1]; + sbusTelemetryData[slotId].slotId = sbus2SlotIds[slotId]; + //sbusTelemetryData[i].payload.data[0] = 0x81; + //sbusTelemetryData[i].payload.data[1] = 0x80; + sbusTelemetryDataUsed[slotId] = 1; + } + +} \ No newline at end of file diff --git a/src/main/telemetry/sbus2_sensors.h b/src/main/telemetry/sbus2_sensors.h new file mode 100644 index 00000000000..f349e389cf9 --- /dev/null +++ b/src/main/telemetry/sbus2_sensors.h @@ -0,0 +1,118 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#include + +#include "platform.h" + +// Sensor code from https://github.com/BrushlessPower/SBUS2-Telemetry +// SBUS2 telemetry: 2ms deadtime after rc package +// One new slot every 700us + +/* + * ++++++++++++++++++++++++++++++++ + * Temperature Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_temp125(uint8_t port, int16_t temp); +void send_alarm_as_temp125(uint8_t port, int16_t alarm); +void send_SBS01TE(uint8_t port, int16_t temp); +void send_SBS01T(uint8_t port, int16_t temp); +void send_F1713(uint8_t port, int16_t temp); + +/* + * ++++++++++++++++++++++++++++++++ + * RPM Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_RPM(uint8_t port, uint32_t RPM); +void send_SBS01RB(uint8_t port, uint32_t RPM); +void send_SBS01RM(uint8_t port, uint32_t RPM); +void send_SBS01RO(uint8_t port, uint32_t RPM); +void send_SBS01R(uint8_t port, uint32_t RPM); + +/* + * ++++++++++++++++++++++++++++++++ + * Voltage/Current Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_voltage(uint8_t port,uint16_t voltage1, uint16_t voltage2); +void send_voltagef(uint8_t port,float voltage1, float voltage2); +void send_s1678_current(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_s1678_currentf(uint8_t port, float current, uint16_t capacity, float voltage); +void send_SBS01C(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_SBS01Cf(uint8_t port, float current, uint16_t capacity, float voltage); +void send_F1678(uint8_t port, uint16_t current, uint16_t capacity, uint16_t voltage); +void send_F1678f(uint8_t port, float current, uint16_t capacity, float voltage); +void send_SBS01V(uint8_t port,uint16_t voltage1, uint16_t voltage2); +void send_SBS01Vf(uint8_t port,float voltage1, float voltage2); + + +/* + * ++++++++++++++++++++++++++++++++ + * Vario Sensors + * ++++++++++++++++++++++++++++++++ + */ +void send_f1712_vario(uint8_t port, int16_t altitude, int16_t vario); +void send_f1712_variof(uint8_t port, int16_t altitude, float vario); +void send_f1672_vario(uint8_t port, int16_t altitude, int16_t vario); +void send_f1672_variof(uint8_t port, int16_t altitude, float vario); +void send_F1712(uint8_t port, int16_t altitude, int16_t vario); +void send_F1712f(uint8_t port, int16_t altitude, float vario); +void send_F1672(uint8_t port, int16_t altitude, int16_t vario); +void send_F1672f(uint8_t port, int16_t altitude, float vario); + +/* + * ++++++++++++++++++++++++++++++++ + * GPS Sensors + * Note the different Input Types! + * Example: + * Position Berlin Fernsehturm + * https://www.koordinaten-umrechner.de/decimal/52.520832,13.409430?karte=OpenStreetMap&zoom=19 + * Degree Minutes 52° 31.2499 and 13° 24.5658 + * Decimal Degree 52.520832 and 13.409430 + * ++++++++++++++++++++++++++++++++ + */ +// Degree Minutes as Integer -> 52312499 +void send_f1675_gps(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); +// Degree Minutes as Integer -> 52 and 312499 +void send_F1675min(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, int32_t lat_min, int8_t lon_deg, int32_t lon_min); +// Degree Minutes as Float -> 52 and 31.2499 +void send_F1675minf(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int8_t lat_deg, float lat_min, int8_t lon_deg, float lon_min); +// Decimal Degrees as Float -> 52.520832 +void send_F1675f(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, float latitude, float longitude); +// Decimal Degrees as Integer -> 52520832 +void send_F1675(uint8_t port, uint16_t speed, int16_t hight, int16_t vario, int32_t latitude, int32_t longitude); +void send_SBS10G(uint8_t port, uint16_t hours, uint16_t minutes, uint16_t seconds, float latitude, float longitude, float altitudeMeters, uint16_t speed, float gpsVario); + +/* + * ++++++++++++++++++++++++++++++++ + * ESC Sensors + * Note These sensors only exists on the newer Futaba Radios 18SZ, 16IZ, etc + * ++++++++++++++++++++++++++++++++ + */ + +void send_kontronik(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); +void send_scorpion(uint8_t port, uint16_t voltage, uint16_t capacity, uint32_t rpm, uint16_t current, uint16_t temp, uint16_t becTemp, uint16_t becCurrent, uint16_t pwm); + +void send_jetcat(uint8_t port, uint32_t rpm, uint16_t egt, uint16_t pump_volt, uint32_t setrpm, uint16_t thrust, uint16_t fuel, uint16_t fuelflow, uint16_t altitude, uint16_t quality, uint16_t volt, uint16_t current, uint16_t speed, uint16_t status, uint32_t secondrpm); + +void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes); + From cf4fab88092f0f27918f66caab149dda51878a8f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 18 Jul 2024 23:38:19 +0200 Subject: [PATCH 121/212] ifdef USE_TELEMETRY_SBUS2 --- src/main/telemetry/sbus2_sensors.c | 5 ++++- src/main/telemetry/sbus2_sensors.h | 3 +++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/telemetry/sbus2_sensors.c b/src/main/telemetry/sbus2_sensors.c index ec3d05a4bd7..f2e94f51ac1 100644 --- a/src/main/telemetry/sbus2_sensors.c +++ b/src/main/telemetry/sbus2_sensors.c @@ -18,6 +18,8 @@ #include "telemetry/sbus2.h" #include "telemetry/sbus2_sensors.h" + +#ifdef USE_TELEMETRY_SBUS2 void send_RPM(uint8_t port, uint32_t RPM) { uint32_t value = 0; @@ -726,4 +728,5 @@ void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes) sbusTelemetryDataUsed[slotId] = 1; } -} \ No newline at end of file +} +#endif \ No newline at end of file diff --git a/src/main/telemetry/sbus2_sensors.h b/src/main/telemetry/sbus2_sensors.h index f349e389cf9..53ffb07aded 100644 --- a/src/main/telemetry/sbus2_sensors.h +++ b/src/main/telemetry/sbus2_sensors.h @@ -22,6 +22,8 @@ #include "platform.h" +#ifdef USE_TELEMETRY_SBUS2 + // Sensor code from https://github.com/BrushlessPower/SBUS2-Telemetry // SBUS2 telemetry: 2ms deadtime after rc package // One new slot every 700us @@ -116,3 +118,4 @@ void send_jetcat(uint8_t port, uint32_t rpm, uint16_t egt, uint16_t pump_volt, u void SBUS2_transmit_telemetry_data(uint8_t slotId , const uint8_t *bytes); +#endif \ No newline at end of file From 711301ef6986cf318ab51ec6d4878b624d0907fb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 17:54:21 +0200 Subject: [PATCH 122/212] Fixed update rate --- src/main/telemetry/sbus2.c | 38 +++++++++++++++++++++++++++++++------- src/main/telemetry/sbus2.h | 7 ++++++- 2 files changed, 37 insertions(+), 8 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index bcdc1368168..7b2168ca486 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -54,11 +54,11 @@ const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { 0x1B, 0x9B, 0x5B, 0xDB, 0x3B, 0xBB, 0x7B, 0xFB }; - - sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT] = {}; uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT] = {}; -timeUs_t sbusTelemetryMinDelay[SBUS2_SLOT_COUNT] = {}; +//timeUs_t sbusTelemetryMinDelay[SBUS2_SLOT_COUNT] = {}; +static uint8_t currentSlot = 0; +static timeUs_t nextSlotTime = 0; void handleSbus2Telemetry(timeUs_t currentTimeUs) { @@ -149,10 +149,21 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) { + UNUSED(elapsed); if (elapsed < SBUS2_DEADTIME) { + currentSlot = 0; + nextSlotTime = 0; return 0xFF; // skip it } + if(currentSlot < SBUS2_TELEMETRY_SLOTS) { + return currentSlot; + } + + return 0xFF; + + /* + elapsed = elapsed - SBUS2_DEADTIME; uint8_t slot = (elapsed % SBUS2_SLOT_TIME) - 1; @@ -162,6 +173,13 @@ uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) } return slot; + */ +} + +void sbus2IncrementTelemetrySlot(timeUs_t currentTimeUs) +{ + nextSlotTime = currentTimeUs + (SBUS2_TRANSMIT_TIME + SBUS2_SLOT_DELAY); + currentSlot++; } FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) @@ -173,10 +191,15 @@ FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) timeUs_t elapsedTime = currentTimeUs - sbusGetLastFrameTime(); - if(elapsedTime > MS2US(8)) { + if (elapsedTime > MS2US(8)) { + currentSlot = 0; + nextSlotTime = 0; return; } + if (currentTimeUs < nextSlotTime) { + return; + } uint8_t telemetryPage = sbusGetCurrentTelemetryPage(); @@ -185,16 +208,17 @@ FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) if(slot < SBUS2_TELEMETRY_SLOTS) { int slotIndex = (telemetryPage * SBUS2_TELEMETRY_SLOTS) + slot; if (slotIndex < SBUS2_SLOT_COUNT) { - if (sbusTelemetryDataUsed[slotIndex] != 0 && sbusTelemetryMinDelay[slotIndex] < currentTimeUs) { - sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; + if (sbusTelemetryDataUsed[slotIndex] != 0) { + //sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; // send serialWriteBuf(telemetrySharedPort, (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); - sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(1); + //sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(1); //sbusTelemetryDataUsed[slotIndex] = 0; } } + sbus2IncrementTelemetrySlot(currentTimeUs); } } diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 9c2c39ba73e..ac538b1c193 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -33,6 +33,10 @@ #define SBUS2_DEADTIME MS2US(2) #define SBUS2_SLOT_TIME 650u + +#define SBUS2_TRANSMIT_TIME ((8 + 1 + 2 + 1 + 1) * 3 * 10) // 8e2, 100000 baud + star and stop bits +#define SBUS2_SLOT_DELAY 200 + #define SBUS2_SLOT_DELAY_MAX (MIN(350u, (SBUS2_SLOT_TIME / 2u))) #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) @@ -55,7 +59,7 @@ STATIC_ASSERT(sizeof(sbus2_telemetry_frame_t) == 3, sbus2_telemetry_size); extern const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT]; extern uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT]; -extern timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT]; +//extern timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT]; // refresh telemetry buffers void handleSbus2Telemetry(timeUs_t currentTimeUs); @@ -64,5 +68,6 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs); void taskSendSbus2Telemetry(timeUs_t currentTimeUs); uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed); +void sbus2IncrementTelemetrySlot(timeUs_t now); #endif From 6d393a700c5e09600d75b1b750697feb5a73bf04 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 17:56:47 +0200 Subject: [PATCH 123/212] Remove dead code --- src/main/telemetry/sbus2.c | 17 ----------------- src/main/telemetry/sbus2.h | 1 - 2 files changed, 18 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 7b2168ca486..fb7ff5dde16 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -56,7 +56,6 @@ const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT] = { sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT] = {}; uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT] = {}; -//timeUs_t sbusTelemetryMinDelay[SBUS2_SLOT_COUNT] = {}; static uint8_t currentSlot = 0; static timeUs_t nextSlotTime = 0; @@ -161,19 +160,6 @@ uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) } return 0xFF; - - /* - - elapsed = elapsed - SBUS2_DEADTIME; - - uint8_t slot = (elapsed % SBUS2_SLOT_TIME) - 1; - - if (elapsed - (slot * SBUS2_SLOT_TIME) > SBUS2_SLOT_DELAY_MAX) { - slot = 0xFF; - } - - return slot; - */ } void sbus2IncrementTelemetrySlot(timeUs_t currentTimeUs) @@ -209,13 +195,10 @@ FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) int slotIndex = (telemetryPage * SBUS2_TELEMETRY_SLOTS) + slot; if (slotIndex < SBUS2_SLOT_COUNT) { if (sbusTelemetryDataUsed[slotIndex] != 0) { - //sbusTelemetryData[slotIndex].slotId = sbus2SlotIds[slotIndex]; // send serialWriteBuf(telemetrySharedPort, (const uint8_t *)&sbusTelemetryData[slotIndex], sizeof(sbus2_telemetry_frame_t)); - //sbusTelemetryMinDelay[slotIndex] = currentTimeUs + MS2US(1); - //sbusTelemetryDataUsed[slotIndex] = 0; } } sbus2IncrementTelemetrySlot(currentTimeUs); diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index ac538b1c193..10e5b35ece0 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -59,7 +59,6 @@ STATIC_ASSERT(sizeof(sbus2_telemetry_frame_t) == 3, sbus2_telemetry_size); extern const uint8_t sbus2SlotIds[SBUS2_SLOT_COUNT]; extern sbus2_telemetry_frame_t sbusTelemetryData[SBUS2_SLOT_COUNT]; extern uint8_t sbusTelemetryDataUsed[SBUS2_SLOT_COUNT]; -//extern timeUs_t sbusTelemetryDataLastSent[SBUS2_SLOT_COUNT]; // refresh telemetry buffers void handleSbus2Telemetry(timeUs_t currentTimeUs); From 062b068bd08f1aa32e1749d3bdbecac36f07d5cd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 17:58:27 +0200 Subject: [PATCH 124/212] Remove old comment --- src/main/telemetry/sbus2.c | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index fb7ff5dde16..7bedd18c0a9 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -141,9 +141,6 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) send_SBS01T(18 + i, 0); } #endif - - // 8 slots - gps - // } uint8_t sbus2GetTelemetrySlot(timeUs_t elapsed) From 7bba2b931e68a9a6756575c7b9eb8cc1c2d0e9ca Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 12:19:10 -0400 Subject: [PATCH 125/212] Update SBUS2_Telemetry.md --- docs/SBUS2_Telemetry.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/SBUS2_Telemetry.md b/docs/SBUS2_Telemetry.md index d8a1cd8f1e1..1a687e99b0b 100644 --- a/docs/SBUS2_Telemetry.md +++ b/docs/SBUS2_Telemetry.md @@ -1,10 +1,10 @@ # Futaba SBUS2 Telemetry -Basic experimental support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is limited to F7 and H7 mcus only. The main reason it is limited to those MCUs is due to it requiring an inverted UART signal, and the SBUS pads in F405 usually are not bi-directional. +Basic experimental support for SBUS2 telemetry has been added to INAV 8.0.0. Currently it is limited to F7 and H7 mcus only. The main reason it is limited to those MCUs is due to the requirement for an inverted UART signal and the SBUS pads in F405 usually are not bi-directional. The basic sensors have been tested with a Futaba T16IZ running software version 6.0E. -An alternative to using INAV's SBUS2 support is to use SBS-01ML MAVlink Telemetry Drone Sensor instead. (not tested) +An alternative to using INAV's SBUS2 support is to use SBS-01ML MAVlink Telemetry Drone Sensor instead. (not tested and not supported with older futaba radios, including my 16IZ). # Wiring The SBUS2 signal should be connected to the TX PIN, not the RX PIN, like on a traditional SBUS setup. From 7eb45b2457cba260b0cbe14c43ecffd5fcff2373 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 18:29:17 +0200 Subject: [PATCH 126/212] Remove unused define --- src/main/telemetry/sbus2.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/telemetry/sbus2.h b/src/main/telemetry/sbus2.h index 10e5b35ece0..0fc74f3298d 100644 --- a/src/main/telemetry/sbus2.h +++ b/src/main/telemetry/sbus2.h @@ -37,8 +37,6 @@ #define SBUS2_TRANSMIT_TIME ((8 + 1 + 2 + 1 + 1) * 3 * 10) // 8e2, 100000 baud + star and stop bits #define SBUS2_SLOT_DELAY 200 -#define SBUS2_SLOT_DELAY_MAX (MIN(350u, (SBUS2_SLOT_TIME / 2u))) - #define SBUS2_SLOT_COUNT (SBUS2_TELEMETRY_PAGES * SBUS2_TELEMETRY_SLOTS) #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) From a617d218a0bd827ff5dff6e4557a217be353e20d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 14:06:43 -0400 Subject: [PATCH 127/212] Update telemetry.c --- src/main/telemetry/telemetry.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index f6ba7f85437..56c18ca159b 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -251,7 +251,6 @@ void telemetryProcess(timeUs_t currentTimeUs) #ifdef USE_TELEMETRY_SBUS2 handleSbus2Telemetry(currentTimeUs); - DEBUG_SET(DEBUG_SBUS2, 7, 1); #endif } From 397a632f0e3bb01bbd7199d684c154a6daa90a79 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 20:33:49 +0200 Subject: [PATCH 128/212] Cleanup --- src/main/telemetry/sbus2.c | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index 7bedd18c0a9..dc5fb81d77d 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -129,6 +129,7 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) valid = 0; valid = getBaroTemperature(&temp16); send_SBS01T(17, valid ? temp16 / 10 : 0); + // temp sensors 18-25 #ifdef USE_TEMPERATURE_SENSOR for(int i = 0; i < 8; i++) { @@ -136,10 +137,6 @@ void handleSbus2Telemetry(timeUs_t currentTimeUs) valid = getSensorTemperature(0, &temp16); send_SBS01T(18 + i, valid ? temp16 / 10 : 0); } -#else - for(int i = 0; i < 8; i++) { - send_SBS01T(18 + i, 0); - } #endif } From cd7e89d8c71e26b171d33e18a513688f40941272 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 20 Jul 2024 21:09:24 +0200 Subject: [PATCH 129/212] Add basic sbus information and link to full docs --- docs/Telemetry.md | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/docs/Telemetry.md b/docs/Telemetry.md index 996630e66fa..a33aa4ee527 100644 --- a/docs/Telemetry.md +++ b/docs/Telemetry.md @@ -390,3 +390,21 @@ In configurator set IBUS telemetry and RX on this same port, enable telemetry fe Warning: Schematic above work also for connect telemetry only, but not work for connect rx only - will stop FC. + + +## Futaba SBUS2 telemetry + +SBUS2 telemetry requires a single connection from the TX pin of a bidirectional serial port to the SBUS2 pin on a Futaba T-FHSS or FASSTest telemetry receiver. (tested T16IZ radio and R7108SB and R3204SB receivers) + +It shares 1 line for both TX and RX, the rx pin cannot be used for other serial port stuff. +It runs at a fixed baud rate of 100000, so it needs a hardware uart capable of inverted signals. It is not available on F4 mcus. + +``` + _______ + / \ /-------------\ + | STM32 |-->UART TX-->[Bi-directional @ 100000 baud]-->| Futaba RX | + | uC |- UART RX--x[not connected] | SBUS2 port | + \_______/ \-------------/ +``` + +For more information and sensor slot numbering, refer to [SBUS2 Documentation](SBUS2_telemetry.md) \ No newline at end of file From 734050e9383c81d58e88d04f9c3421e01645129c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 21 Jul 2024 19:07:36 +0200 Subject: [PATCH 130/212] Lower sbus2 telemetry trask priority --- src/main/fc/fc_tasks.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 7a456699fa9..107a0e732b6 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -733,10 +733,10 @@ cfTask_t cfTasks[TASK_COUNT] = { #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) [TASK_TELEMETRY_SBUS2] = { - .taskName = "SBUS2_TELEMETRY", + .taskName = "SBUS2 TLM", .taskFunc = taskSendSbus2Telemetry, .desiredPeriod = TASK_PERIOD_US(125), // 8kHz 2ms dead time + 650us window / sensor. - .staticPriority = TASK_PRIORITY_REALTIME, // timing is critical. Ideally, should be a timer interrupt triggered by sbus packet + .staticPriority = TASK_PRIORITY_LOW, // timing is critical. Ideally, should be a timer interrupt triggered by sbus packet }, #endif From 7d5d8f27997d6a1bc247053b8828acc2d685abd2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 22 Jul 2024 18:15:58 -0400 Subject: [PATCH 131/212] Update Serial Gimbal.md Fix typos --- docs/Serial Gimbal.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Serial Gimbal.md b/docs/Serial Gimbal.md index 984e00f29d1..c2c35b90af1 100644 --- a/docs/Serial Gimbal.md +++ b/docs/Serial Gimbal.md @@ -17,7 +17,7 @@ In head tracker mode, the Serial Gimbal will ignore the axis rc channel inputs a # Gimbal Modes ## No Gimbal mode selected -Like ACRO is the default mode for flight modes, the Gimbal will default to ```FPV Mode``` or ```Follow Mode``` when no mode is selected. The gimbal will try to stablized the footag and will follow the aircraft pitch, roll and yaw movements and use user inputs to point the camera where the user wants. +Like ACRO is the default mode for flight modes, the Gimbal will default to ```FPV Mode``` or ```Follow Mode``` when no mode is selected. The gimbal will try to stablized the footage and will follow the aircraft pitch, roll and yaw movements and use user inputs to point the camera where the user wants. ## Gimbal Center This locks the gimbal camera to the center position and ignores any user input. Useful to reset the camera if you loose orientation. @@ -49,7 +49,7 @@ Allowed range: -500 - 500 ``` ## Gimbal and Headtracker on a single uart -As INAV does not process any inputs from the Walksnail Gimbal, it is possible to share the uard with the Walksnail Headtracking output by connect the fc TX to the gimbal and RX to receive the headtracker input. +As INAV does not process any inputs from the Walksnail Gimbal, it is possible to share the uart with the Walksnail Headtracking output by connect the fc TX to the gimbal and RX to receive the headtracker input. ``` gimbal_serial_single_uart = OFF Allowed values: OFF, ON From b3f060d9ef4d999ef38c0995a325cfc6bc7ba248 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 23 Jul 2024 10:45:04 +0200 Subject: [PATCH 132/212] Make sure DEFAULT_I2C_DEVICE is always valid --- src/main/target/KAKUTEF4WING/target.h | 2 ++ src/main/target/common_post.h | 16 ++++++++++++++++ 2 files changed, 18 insertions(+) diff --git a/src/main/target/KAKUTEF4WING/target.h b/src/main/target/KAKUTEF4WING/target.h index 70eb125646a..cd8b74ac13d 100644 --- a/src/main/target/KAKUTEF4WING/target.h +++ b/src/main/target/KAKUTEF4WING/target.h @@ -45,6 +45,8 @@ #define I2C2_SCL PB10 #define I2C2_SDA PB11 +#define DEFAULT_I2C_BUS BUS_I2C2 + // ********** External MAG On I2C2****** #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index d3ccf280b17..9a85d14f1ee 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -29,6 +29,22 @@ extern uint8_t __config_end; # undef USE_OLED_UG2864 #endif + +// Make sure DEFAULT_I2C_BUS is valid +#ifndef DEFAULT_I2C_BUS + +#ifdef USE_I2C_DEVICE_1 +#define DEFAULT_I2C_BUS BUS_I2C1 +#elif USE_I2C_DEVICE_2 +#define DEFAULT_I2C_BUS BUS_I2C2 +#elif USE_I2C_DEVICE_3 +#define DEFAULT_I2C_BUS BUS_I2C3 +#elif USE_I2C_DEVICE_4 +#define DEFAULT_I2C_BUS BUS_I2C4 +#endif + +#endif + // Enable MSP_DISPLAYPORT for F3 targets without builtin OSD, // since it's used to display CMS on MWOSD #if !defined(USE_MSP_DISPLAYPORT) && !defined(USE_OSD) From 0b207ac02d66ea667a32f22a27f633ce4b84b745 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 23 Jul 2024 11:59:35 +0200 Subject: [PATCH 133/212] Use default_i2c_bus when available --- src/main/target/common_post.h | 25 +++++++++++++++++++++---- 1 file changed, 21 insertions(+), 4 deletions(-) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 9a85d14f1ee..fc3859977ed 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -33,18 +33,35 @@ extern uint8_t __config_end; // Make sure DEFAULT_I2C_BUS is valid #ifndef DEFAULT_I2C_BUS -#ifdef USE_I2C_DEVICE_1 +#if defined(USE_I2C_DEVICE_1) #define DEFAULT_I2C_BUS BUS_I2C1 -#elif USE_I2C_DEVICE_2 +#elif defined(USE_I2C_DEVICE_2) #define DEFAULT_I2C_BUS BUS_I2C2 -#elif USE_I2C_DEVICE_3 +#elif defined(USE_I2C_DEVICE_3) #define DEFAULT_I2C_BUS BUS_I2C3 -#elif USE_I2C_DEVICE_4 +#elif defined(USE_I2C_DEVICE_4) #define DEFAULT_I2C_BUS BUS_I2C4 #endif #endif +// Airspeed sensors +#if defined(USE_PITOT) && defined(DEFAULT_I2C_BUS) + +#ifndef PITOT_I2C_BUS +#define PITOT_I2C_BUS DEFAULT_I2C_BUS +#endif + +#endif + +// Temperature sensors +#if !defined(TEMPERATURE_I2C_BUS) && defined(DEFAULT_I2C_BUS) + +#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS + +#endif + + // Enable MSP_DISPLAYPORT for F3 targets without builtin OSD, // since it's used to display CMS on MWOSD #if !defined(USE_MSP_DISPLAYPORT) && !defined(USE_OSD) From 5d2fb24bc19abb639ac45345e446fa9d09e6709f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 23 Jul 2024 12:05:49 +0200 Subject: [PATCH 134/212] Add DEFAULT_I2C_BUS and make sure we default to a valid i2c bus --- src/main/target/common_post.h | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index fc3859977ed..fddd8b2a906 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -56,11 +56,13 @@ extern uint8_t __config_end; // Temperature sensors #if !defined(TEMPERATURE_I2C_BUS) && defined(DEFAULT_I2C_BUS) - #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS - #endif +// Rangefinder sensors +#if !defined(RANGEFINDER_I2C_BUS) && defined(DEFAULT_I2C_BUS) +#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS +#endif // Enable MSP_DISPLAYPORT for F3 targets without builtin OSD, // since it's used to display CMS on MWOSD @@ -100,6 +102,10 @@ extern uint8_t __config_end; #endif // USE_MAG_ALL +#if defined(DEFAULT_I2C_BUS) && !defined(MAG_I2C_BUS) +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#endif + #endif // USE_MAG #if defined(USE_BARO) @@ -117,6 +123,10 @@ extern uint8_t __config_end; #define USE_BARO_SPL06 #endif +#if defined(DEFAULT_I2C_BUS) && !defined(BARO_I2C_BUS) +#define BARO_I2C_BUS DEFAULT_I2C_BUS +#endif + #endif #ifdef USE_ESC_SENSOR From 4c497046747235f09d2e5f6d202b152ac2eb769d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 23 Jul 2024 12:15:04 +0200 Subject: [PATCH 135/212] Make sure all i2c devices are setup correctly --- src/main/target/KAKUTEF4WING/target.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/KAKUTEF4WING/target.h b/src/main/target/KAKUTEF4WING/target.h index cd8b74ac13d..70eb125646a 100644 --- a/src/main/target/KAKUTEF4WING/target.h +++ b/src/main/target/KAKUTEF4WING/target.h @@ -45,8 +45,6 @@ #define I2C2_SCL PB10 #define I2C2_SDA PB11 -#define DEFAULT_I2C_BUS BUS_I2C2 - // ********** External MAG On I2C2****** #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 From db023eccc87b75bc0fb0f64a7b460e36c639b83c Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Fri, 26 Jul 2024 11:39:37 -0500 Subject: [PATCH 136/212] AOCODARCF7MINI_V1: DSHOT_DMAR and V1 output order --- src/main/target/AOCODARCF7MINI/target.c | 4 +++- src/main/target/AOCODARCF7MINI/target.h | 4 ++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/target/AOCODARCF7MINI/target.c b/src/main/target/AOCODARCF7MINI/target.c index f01d2c73e81..72140f50fac 100644 --- a/src/main/target/AOCODARCF7MINI/target.c +++ b/src/main/target/AOCODARCF7MINI/target.c @@ -47,11 +47,13 @@ timerHardware_t timerHardware[] = { #if defined(AOCODARCF7MINI_V2) DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2, 4, 7) DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(2, 7, 7) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2) #else + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1, 6, 3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 #endif - DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2) DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/AOCODARCF7MINI/target.h b/src/main/target/AOCODARCF7MINI/target.h index 9f628963d85..4a5f5068746 100644 --- a/src/main/target/AOCODARCF7MINI/target.h +++ b/src/main/target/AOCODARCF7MINI/target.h @@ -163,3 +163,7 @@ #define USE_DSHOT #define USE_SERIALSHOT #define USE_ESC_SENSOR + +#if defined(AOCODARCF7MINI_V1) +#define USE_DSHOT_DMAR +#endif From 4b47e89d1a13c65d81a35f66d9e64feea9b27c62 Mon Sep 17 00:00:00 2001 From: MUSTARDTIGER FPV <122312693+MUSTARDTIGERFPV@users.noreply.github.com> Date: Sat, 27 Jul 2024 09:09:40 -0700 Subject: [PATCH 137/212] Change MAVLink component ID to be a "proper" autopilot - makes QGC & mLRS work properly. --- src/main/telemetry/mavlink.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 8931ed83c83..c8f5600d6e6 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -184,7 +184,7 @@ static mavlink_message_t mavRecvMsg; static mavlink_status_t mavRecvStatus; static uint8_t mavSystemId = 1; -static uint8_t mavComponentId = MAV_COMP_ID_SYSTEM_CONTROL; +static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1; static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode) { From 13edf9c0569b2b786f1537c0c6f26c4b951c2280 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Tue, 30 Jul 2024 07:19:38 +0200 Subject: [PATCH 138/212] sa: increase MAX_POWER_COUNT to 8 --- src/main/io/vtx_smartaudio.c | 7 +++++-- src/main/io/vtx_smartaudio.h | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 9901db409e2..20997c2da2c 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -73,7 +73,7 @@ static vtxDevice_t vtxSmartAudio = { .vTable = &saVTable, .capability.bandCount = VTX_SMARTAUDIO_BAND_COUNT, .capability.channelCount = VTX_SMARTAUDIO_CHANNEL_COUNT, - .capability.powerCount = VTX_SMARTAUDIO_MAX_POWER_COUNT, + .capability.powerCount = VTX_SMARTAUDIO_MAX_POWER_COUNT, // Should this be VTX_SMARTAUDIO_DEFAULT_POWER_COUNT? .capability.bandNames = (char **)vtx58BandNames, .capability.channelNames = (char **)vtx58ChannelNames, .capability.powerNames = (char**)saPowerNames @@ -124,7 +124,10 @@ saPowerTable_t saPowerTable[VTX_SMARTAUDIO_MAX_POWER_COUNT] = { { 200, 16 }, { 500, 25 }, { 800, 40 }, - { 0, 0 } // Placeholder + { 0, 0 }, // Placeholders + { 0, 0 }, + { 0, 0 }, + { 0, 0 } }; // Last received device ('hard') states diff --git a/src/main/io/vtx_smartaudio.h b/src/main/io/vtx_smartaudio.h index c817f05a79f..ba8856b0faf 100644 --- a/src/main/io/vtx_smartaudio.h +++ b/src/main/io/vtx_smartaudio.h @@ -33,7 +33,7 @@ #define VTX_SMARTAUDIO_BAND_COUNT (VTX_SMARTAUDIO_MAX_BAND - VTX_SMARTAUDIO_MIN_BAND + 1) #define VTX_SMARTAUDIO_CHANNEL_COUNT (VTX_SMARTAUDIO_MAX_CHANNEL - VTX_SMARTAUDIO_MIN_CHANNEL + 1) -#define VTX_SMARTAUDIO_MAX_POWER_COUNT 5 +#define VTX_SMARTAUDIO_MAX_POWER_COUNT 8 #define VTX_SMARTAUDIO_DEFAULT_POWER_COUNT 4 #define VTX_SMARTAUDIO_DEFAULT_POWER 1 From 86fe389b0c97bf6e89963c3f872062f7aeb0de1e Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 30 Jul 2024 18:11:48 +0100 Subject: [PATCH 139/212] add additional BBL headers for MAX SERVO increase (#10263) --- src/main/blackbox/blackbox.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 324b41a1095..5a72d323b09 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -350,6 +350,8 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 13, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, {"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, @@ -406,7 +408,7 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = { * but name kept for external compatibility reasons. * "activeFlightModeFlags" logs actual active flight modes rather than rc boxmodes. * 'active' should at least distinguish it from the existing "flightModeFlags" */ - + {"activeWpNumber", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, {"flightModeFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, {"flightModeFlags2", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, From 6670fe3e71ce5b817e217187fa863e520379aaba Mon Sep 17 00:00:00 2001 From: b14ckyy Date: Tue, 30 Jul 2024 22:50:31 +0200 Subject: [PATCH 140/212] Removed WP uploade blcoker when armed --- src/main/navigation/navigation.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index adcecede5fe..82452256a51 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3703,7 +3703,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) setDesiredPosition(&wpPos.pos, DEGREES_TO_CENTIDEGREES(wpData->p1), waypointUpdateFlags); } // WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission - else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) { + else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS)) { // && !ARMING_FLAG(ARMED) if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) static int8_t nonGeoWaypointCount = 0; From b54a1c9526277a347057ea3b9a5833e220a16d69 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 00:25:17 +0200 Subject: [PATCH 141/212] Refactor sbus to support futaba's 26 (36 channel version) --- src/main/io/servo_sbus.c | 4 +-- src/main/rx/sbus.c | 57 +++++++++++++++++++++++++++++++++++-- src/main/rx/sbus_channels.c | 52 +++++++++++++++++++++++++++++++-- src/main/rx/sbus_channels.h | 11 ++++--- 4 files changed, 114 insertions(+), 10 deletions(-) diff --git a/src/main/io/servo_sbus.c b/src/main/io/servo_sbus.c index bfcd71b1158..121025c71a3 100644 --- a/src/main/io/servo_sbus.c +++ b/src/main/io/servo_sbus.c @@ -109,8 +109,8 @@ void sbusServoUpdate(uint8_t index, uint16_t value) case 13: sbusFrame.channels.chan13 = sbusEncodeChannelValue(value); break; case 14: sbusFrame.channels.chan14 = sbusEncodeChannelValue(value); break; case 15: sbusFrame.channels.chan15 = sbusEncodeChannelValue(value); break; - case 16: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_17) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_17) ; break; - case 17: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_18) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_18) ; break; + case 16: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_DG1) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_DG1) ; break; + case 17: sbusFrame.channels.flags = value > PWM_RANGE_MIDDLE ? (sbusFrame.channels.flags | SBUS_FLAG_CHANNEL_DG2) : (sbusFrame.channels.flags & ~SBUS_FLAG_CHANNEL_DG2) ; break; default: break; } diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 9c0fa30bd11..df22dab3e6b 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -54,6 +54,8 @@ typedef enum { STATE_SBUS_SYNC = 0, STATE_SBUS_PAYLOAD, + STATE_SBUS26_PAYLOAD_LOW, + STATE_SBUS26_PAYLOAD_HIGH, STATE_SBUS_WAIT_SYNC } sbusDecoderState_e; @@ -61,7 +63,8 @@ typedef struct sbusFrameData_s { sbusDecoderState_e state; volatile sbusFrame_t frame; volatile bool frameDone; - uint8_t buffer[SBUS_FRAME_SIZE]; + volatile bool is26channels; + uint8_t buffer[SBUS26_FRAME_SIZE]; uint8_t position; timeUs_t lastActivityTimeUs; } sbusFrameData_t; @@ -89,6 +92,14 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; + } else if (c == SBUS26_FRAME0_BEGIN_BYTE) { + sbusFrameData->position = 0; + sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; + sbusFrameData->state = STATE_SBUS26_PAYLOAD_LOW; + } else if (c == SBUS26_FRAME1_BEGIN_BYTE) { + sbusFrameData->position = 0; + sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; + sbusFrameData->state = STATE_SBUS26_PAYLOAD_HIGH; } break; @@ -130,10 +141,50 @@ static void sbusDataReceive(uint16_t c, void *data) memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE); sbusFrameData->frameDone = true; + sbusFrameData->is26channels = false; + } + } + break; + + case STATE_SBUS26_PAYLOAD_LOW: + case STATE_SBUS26_PAYLOAD_HIGH: + sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; + + if (sbusFrameData->position == SBUS_FRAME_SIZE) { + const sbusFrame_t * frame = (sbusFrame_t *)&sbusFrameData->buffer[0]; + bool frameValid = false; + + // Do some sanity check + switch (frame->endByte) { + case 0x20: // S.BUS 2 telemetry page 1 + case 0x24: // S.BUS 2 telemetry page 2 + case 0x28: // S.BUS 2 telemetry page 3 + case 0x2C: // S.BUS 2 telemetry page 4 + if (frame->syncByte == SBUS26_FRAME1_BEGIN_BYTE) { + sbus2ActiveTelemetryPage = (frame->endByte >> 2) & 0x3; + frameTime = currentTimeUs; + } + + frameValid = true; + sbusFrameData->state = STATE_SBUS_WAIT_SYNC; + break; + + default: // Failed end marker + sbusFrameData->state = STATE_SBUS_WAIT_SYNC; + break; + } + + // Frame seems sane, pass data to decoder + if (!sbusFrameData->frameDone && frameValid) { + memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE); + sbusFrameData->frameDone = true; + sbusFrameData->is26channels = true; } } break; + + case STATE_SBUS_WAIT_SYNC: // Stay at this state and do nothing. Exit will be handled before byte is processed if the // inter-frame gap is long enough @@ -150,7 +201,9 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) } // Decode channel data and store return value - const uint8_t retValue = sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels); + const uint8_t retValue = sbusFrameData->is26channels ? + sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, (sbusFrameData->frame.syncByte == SBUS26_FRAME1_BEGIN_BYTE)) : + sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels); // Reset the frameDone flag - tell ISR that we're ready to receive next frame sbusFrameData->frameDone = false; diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index 99ca76393d6..8697544a08f 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -34,6 +34,54 @@ STATIC_ASSERT(SBUS_FRAME_SIZE == sizeof(sbusFrame_t), SBUS_FRAME_SIZE_doesnt_match_sbusFrame_t); +uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels, bool highChannels) +{ + uint8_t offset = highChannels ? 16 : 0 + uint16_t *sbusChannelData = rxRuntimeConfig->channelData; + sbusChannelData[0 + offset] = channels->chan0; + sbusChannelData[1 + offset] = channels->chan1; + sbusChannelData[2 + offset] = channels->chan2; + sbusChannelData[3 + offset] = channels->chan3; + sbusChannelData[4 + offset] = channels->chan4; + sbusChannelData[5 + offset] = channels->chan5; + sbusChannelData[6 + offset] = channels->chan6; + sbusChannelData[7 + offset] = channels->chan7; + sbusChannelData[8 + offset] = channels->chan8; + sbusChannelData[9 + offset] = channels->chan9; + sbusChannelData[10 + offset] = channels->chan10; + sbusChannelData[11 + offset] = channels->chan11; + sbusChannelData[12 + offset] = channels->chan12; + sbusChannelData[13 + offset] = channels->chan13; + sbusChannelData[14 + offset] = channels->chan14; + sbusChannelData[15 + offset] = channels->chan15; + + offset = highChannels ? 0 : 2; + if (channels->flags & SBUS_FLAG_CHANNEL_DG1) { + sbusChannelData[32 + offset] = SBUS_DIGITAL_CHANNEL_MAX; + } else { + sbusChannelData[32 + offset] = SBUS_DIGITAL_CHANNEL_MIN; + } + + if (channels->flags & SBUS_FLAG_CHANNEL_DG2) { + sbusChannelData[33 + offset] = SBUS_DIGITAL_CHANNEL_MAX; + } else { + sbusChannelData[33 + offset] = SBUS_DIGITAL_CHANNEL_MIN; + } + + if (channels->flags & SBUS_FLAG_FAILSAFE_ACTIVE) { + // internal failsafe enabled and rx failsafe flag set + // RX *should* still be sending valid channel data, so use it. + return RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE; + } + + if (channels->flags & SBUS_FLAG_SIGNAL_LOSS) { + // The received data is a repeat of the last valid data so can be considered complete. + return RX_FRAME_COMPLETE | RX_FRAME_DROPPED; + } + + return RX_FRAME_COMPLETE; +} + uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels) { uint16_t *sbusChannelData = rxRuntimeConfig->channelData; @@ -54,13 +102,13 @@ uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannel sbusChannelData[14] = channels->chan14; sbusChannelData[15] = channels->chan15; - if (channels->flags & SBUS_FLAG_CHANNEL_17) { + if (channels->flags & SBUS_FLAG_CHANNEL_DG1) { sbusChannelData[16] = SBUS_DIGITAL_CHANNEL_MAX; } else { sbusChannelData[16] = SBUS_DIGITAL_CHANNEL_MIN; } - if (channels->flags & SBUS_FLAG_CHANNEL_18) { + if (channels->flags & SBUS_FLAG_CHANNEL_DG2) { sbusChannelData[17] = SBUS_DIGITAL_CHANNEL_MAX; } else { sbusChannelData[17] = SBUS_DIGITAL_CHANNEL_MIN; diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index 467fdda5afc..d8070704052 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -20,17 +20,19 @@ #include #include "rx/rx.h" -#define SBUS_MAX_CHANNEL 18 +#define SBUS_MAX_CHANNEL 36 -#define SBUS_FLAG_CHANNEL_17 (1 << 0) -#define SBUS_FLAG_CHANNEL_18 (1 << 1) +#define SBUS_FLAG_CHANNEL_DG1 (1 << 0) +#define SBUS_FLAG_CHANNEL_DG2 (1 << 1) #define SBUS_FLAG_SIGNAL_LOSS (1 << 2) #define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3) #define SBUS_CHANNEL_DATA_LENGTH sizeof(sbusChannels_t) #define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2) -#define SBUS_FRAME_BEGIN_BYTE 0x0F +#define SBUS_FRAME_BEGIN_BYTE 0x0F +#define SBUS26_FRAME0_BEGIN_BYTE 0xF4 +#define SBUS26_FRAME1_BEGIN_BYTE 0xF0 #define SBUS_BAUDRATE 100000 #define SBUS_BAUDRATE_FAST 200000 @@ -78,5 +80,6 @@ uint16_t sbusDecodeChannelValue(uint16_t sbusValue, bool safeValuesOnly); uint16_t sbusEncodeChannelValue(uint16_t rcValue); uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels); +uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels, bool highChannels); void sbusChannelsInit(rxRuntimeConfig_t *rxRuntimeConfig); From 73f8b03940192a76bf50bb55b84e7878fad46679 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 00:30:26 +0200 Subject: [PATCH 142/212] Adding missing commits --- src/main/rx/sbus.c | 2 +- src/main/rx/sbus_channels.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index df22dab3e6b..9b24361a091 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -64,7 +64,7 @@ typedef struct sbusFrameData_s { volatile sbusFrame_t frame; volatile bool frameDone; volatile bool is26channels; - uint8_t buffer[SBUS26_FRAME_SIZE]; + uint8_t buffer[SBUS_FRAME_SIZE]; uint8_t position; timeUs_t lastActivityTimeUs; } sbusFrameData_t; diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index 8697544a08f..01c9aab5baa 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -36,7 +36,7 @@ STATIC_ASSERT(SBUS_FRAME_SIZE == sizeof(sbusFrame_t), SBUS_FRAME_SIZE_doesnt_mat uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels, bool highChannels) { - uint8_t offset = highChannels ? 16 : 0 + uint8_t offset = highChannels ? 16 : 0; uint16_t *sbusChannelData = rxRuntimeConfig->channelData; sbusChannelData[0 + offset] = channels->chan0; sbusChannelData[1 + offset] = channels->chan1; From 63c090e7ed246a8b3437100114f5229edef7134d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 01:05:43 +0200 Subject: [PATCH 143/212] commence breakage --- src/main/drivers/pwm_mapping.h | 2 +- src/main/flight/servos.h | 14 +++++++++++++- src/main/rx/sbus.c | 8 ++++---- src/main/rx/sbus_channels.c | 8 +++++--- 4 files changed, 23 insertions(+), 9 deletions(-) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 08123130f2c..161735a4431 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -28,7 +28,7 @@ #define MAX_MOTORS 12 #endif -#define MAX_SERVOS 18 +#define MAX_SERVOS 36 #define PWM_TIMER_HZ 1000000 diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 4f6e5777967..5a161d6e4aa 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -20,7 +20,7 @@ #include "config/parameter_group.h" #include "programming/logic_condition.h" -#define MAX_SUPPORTED_SERVOS 18 +#define MAX_SUPPORTED_SERVOS 36 // These must be consecutive typedef enum { @@ -75,6 +75,18 @@ typedef enum { INPUT_RC_CH22 = 47, INPUT_RC_CH23 = 48, INPUT_RC_CH24 = 49, + INPUT_RC_CH25 = 50, + INPUT_RC_CH26 = 51, + INPUT_RC_CH27 = 52, + INPUT_RC_CH28 = 53, + INPUT_RC_CH29 = 54, + INPUT_RC_CH30 = 55, + INPUT_RC_CH31 = 56, + INPUT_RC_CH32 = 57, + INPUT_RC_CH33 = 58, + INPUT_RC_CH34 = 59, + INPUT_RC_CH35 = 60, + INPUT_RC_CH36 = 61, #endif INPUT_SOURCE_COUNT } inputSource_e; diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 9b24361a091..27fa927b9b9 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -88,11 +88,12 @@ static void sbusDataReceive(uint16_t c, void *data) switch (sbusFrameData->state) { case STATE_SBUS_SYNC: - if (c == SBUS_FRAME_BEGIN_BYTE) { + // Ignore non 26 channel packets + if (c == SBUS_FRAME_BEGIN_BYTE && !sbusFrameData->is26channels) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if (c == SBUS26_FRAME0_BEGIN_BYTE) { + } else if (c == SBUS26_FRAME0_BEGIN_BYTE && false) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS26_PAYLOAD_LOW; @@ -141,7 +142,6 @@ static void sbusDataReceive(uint16_t c, void *data) memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE); sbusFrameData->frameDone = true; - sbusFrameData->is26channels = false; } } break; @@ -221,7 +221,7 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, uint32_t sbusBaudRate) { static uint16_t sbusChannelData[SBUS_MAX_CHANNEL]; - static sbusFrameData_t sbusFrameData; + static sbusFrameData_t sbusFrameData = { .is26channels = false}; rxRuntimeConfig->channelData = sbusChannelData; rxRuntimeConfig->frameData = &sbusFrameData; diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index 01c9aab5baa..60f10737996 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -68,18 +68,20 @@ uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChann sbusChannelData[33 + offset] = SBUS_DIGITAL_CHANNEL_MIN; } + uint8_t ret = 0; + if (channels->flags & SBUS_FLAG_FAILSAFE_ACTIVE) { // internal failsafe enabled and rx failsafe flag set // RX *should* still be sending valid channel data, so use it. - return RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE; + ret = RX_FRAME_FAILSAFE; } if (channels->flags & SBUS_FLAG_SIGNAL_LOSS) { // The received data is a repeat of the last valid data so can be considered complete. - return RX_FRAME_COMPLETE | RX_FRAME_DROPPED; + ret = RX_FRAME_DROPPED; } - return RX_FRAME_COMPLETE; + return ret | (highChannels ? RX_FRAME_COMPLETE : RX_FRAME_PENDING); } uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels) From bab0c9c5296943f63fb168779088523a02fc7d14 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 01:10:10 +0200 Subject: [PATCH 144/212] remove test code --- src/main/rx/sbus.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 27fa927b9b9..70427932493 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -93,7 +93,7 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if (c == SBUS26_FRAME0_BEGIN_BYTE && false) { + } else if (c == SBUS26_FRAME0_BEGIN_BYTE) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS26_PAYLOAD_LOW; From 81bed958d4f3e80e2bcf17365cccb2021febceb6 Mon Sep 17 00:00:00 2001 From: MUSTARDTIGERFPV Date: Thu, 1 Aug 2024 02:35:42 +0000 Subject: [PATCH 145/212] Allow serialpassthrough to set parity & stop bits --- docs/Cli.md | 2 +- src/main/drivers/serial.c | 5 +++ src/main/drivers/serial.h | 3 ++ src/main/drivers/serial_softserial.c | 6 +++ src/main/drivers/serial_tcp.c | 7 +++ src/main/drivers/serial_uart.c | 8 ++++ src/main/drivers/serial_uart_hal.c | 8 ++++ src/main/drivers/serial_uart_hal_at32f43x.c | 8 ++++ src/main/drivers/serial_usb_vcp.c | 9 ++++ src/main/drivers/serial_usb_vcp_at32f43x.c | 7 +++ src/main/fc/cli.c | 49 ++++++++++++++++++++- 11 files changed, 109 insertions(+), 3 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index 6a48244a13a..2e45ae138f7 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -107,7 +107,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0 | `save` | Save and reboot | | `sd_info` | Sdcard info | | `serial` | Configure serial ports. [Usage](Serial.md) | -| `serialpassthrough` | Passthrough serial data to port, with ` `, where `id` is the zero based port index, `baud` is a standard baud rate, and mode is `rx`, `tx`, or both (`rxtx`) | +| `serialpassthrough` | Passthrough serial data to port, with ` `, where `id` is the zero based port index, `baud` is a standard baud rate, mode is `rx`, `tx`, or both (`rxtx`), and options is a short string like `8N1` or `8E2` | | `servo` | Configure servos | | `set` | Change setting with name=value or blank or * for list | | `smix` | Custom servo mixer | diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index 165f9c31698..dc625aaa354 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -86,6 +86,11 @@ void serialSetMode(serialPort_t *instance, portMode_t mode) instance->vTable->setMode(instance, mode); } +void serialSetOptions(serialPort_t *instance, portOptions_t options) +{ + instance->vTable->setOptions(instance, options); +} + void serialWriteBufShim(void *instance, const uint8_t *data, int count) { serialWriteBuf((serialPort_t *)instance, data, count); diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index fcb787ded99..8e66b5f8445 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -95,6 +95,8 @@ struct serialPortVTable { void (*setMode)(serialPort_t *instance, portMode_t mode); + void (*setOptions)(serialPort_t *instance, portOptions_t options); + void (*writeBuf)(serialPort_t *instance, const void *data, int count); bool (*isConnected)(const serialPort_t *instance); @@ -113,6 +115,7 @@ void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count); uint8_t serialRead(serialPort_t *instance); void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate); void serialSetMode(serialPort_t *instance, portMode_t mode); +void serialSetOptions(serialPort_t *instance, portOptions_t options); bool isSerialTransmitBufferEmpty(const serialPort_t *instance); void serialPrint(serialPort_t *instance, const char *str); uint32_t serialGetBaudRate(serialPort_t *instance); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 7ce128516f0..09352f4d61b 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -623,6 +623,11 @@ void softSerialSetMode(serialPort_t *instance, portMode_t mode) instance->mode = mode; } +void softSerialSetOptions(serialPort_t *instance, portOptions_t options) +{ + instance->options = options; +} + bool isSoftSerialTransmitBufferEmpty(const serialPort_t *instance) { return instance->txBufferHead == instance->txBufferTail; @@ -636,6 +641,7 @@ static const struct serialPortVTable softSerialVTable = { .serialSetBaudRate = softSerialSetBaudRate, .isSerialTransmitBufferEmpty = isSoftSerialTransmitBufferEmpty, .setMode = softSerialSetMode, + .setOptions = softSerialSetOptions, .isConnected = NULL, .writeBuf = NULL, .beginWrite = NULL, diff --git a/src/main/drivers/serial_tcp.c b/src/main/drivers/serial_tcp.c index 765f8308cd3..915f2a53605 100644 --- a/src/main/drivers/serial_tcp.c +++ b/src/main/drivers/serial_tcp.c @@ -317,6 +317,12 @@ void tcpSetMode(serialPort_t *instance, portMode_t mode) UNUSED(mode); } +void tcpSetOptions(serialPort_t *instance, portOptions_t options) +{ + UNUSED(instance); + UNUSED(options); +} + static const struct serialPortVTable tcpVTable[] = { { .serialWrite = tcpWrite, @@ -326,6 +332,7 @@ static const struct serialPortVTable tcpVTable[] = { .serialSetBaudRate = tcpSetBaudRate, .isSerialTransmitBufferEmpty = isTcpTransmitBufferEmpty, .setMode = tcpSetMode, + .setOptions = tcpSetOptions, .isConnected = tcpIsConnected, .writeBuf = tcpWritBuf, .beginWrite = NULL, diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 7b9bbd7128e..9307b0cab8b 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -175,6 +175,13 @@ void uartSetMode(serialPort_t *instance, portMode_t mode) uartReconfigure(uartPort); } +void uartSetOptions(serialPort_t *instance, portOptions_t options) +{ + uartPort_t *uartPort = (uartPort_t *)instance; + uartPort->port.options = options; + uartReconfigure(uartPort); +} + uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) { const uartPort_t *s = (const uartPort_t*)instance; @@ -255,6 +262,7 @@ const struct serialPortVTable uartVTable[] = { .serialSetBaudRate = uartSetBaudRate, .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, .setMode = uartSetMode, + .setOptions = uartSetOptions, .isConnected = NULL, .writeBuf = NULL, .beginWrite = NULL, diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/serial_uart_hal.c index b1df6ed7541..cce38422848 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -185,6 +185,13 @@ void uartSetMode(serialPort_t *instance, portMode_t mode) uartReconfigure(uartPort); } +void uartSetOptions(serialPort_t *instance, portOptions_t options) +{ + uartPort_t *uartPort = (uartPort_t *)instance; + uartPort->port.options = options; + uartReconfigure(uartPort); +} + uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) { uartPort_t *s = (uartPort_t*)instance; @@ -266,6 +273,7 @@ const struct serialPortVTable uartVTable[] = { .serialSetBaudRate = uartSetBaudRate, .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, .setMode = uartSetMode, + .setOptions = uartSetOptions, .isConnected = NULL, .writeBuf = NULL, .beginWrite = NULL, diff --git a/src/main/drivers/serial_uart_hal_at32f43x.c b/src/main/drivers/serial_uart_hal_at32f43x.c index 0e0f11b1c13..a06869ba10c 100644 --- a/src/main/drivers/serial_uart_hal_at32f43x.c +++ b/src/main/drivers/serial_uart_hal_at32f43x.c @@ -178,6 +178,13 @@ void uartSetMode(serialPort_t *instance, portMode_t mode) uartReconfigure(uartPort); } +void uartSetOptions(serialPort_t *instance, portOptions_t options) +{ + uartPort_t *uartPort = (uartPort_t *)instance; + uartPort->port.options = options; + uartReconfigure(uartPort); +} + uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) { const uartPort_t *s = (const uartPort_t*)instance; @@ -260,6 +267,7 @@ const struct serialPortVTable uartVTable[] = { .serialSetBaudRate = uartSetBaudRate, .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty, .setMode = uartSetMode, + .setOptions = uartSetOptions, .isConnected = NULL, .writeBuf = NULL, .beginWrite = NULL, diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index a90633d6cfd..7fdbad2a114 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -67,6 +67,14 @@ static void usbVcpSetMode(serialPort_t *instance, portMode_t mode) // TODO implement } +static void usbVcpSetOptions(serialPort_t *instance, portOptions_t options) +{ + UNUSED(instance); + UNUSED(options); + + // TODO implement +} + static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance) { UNUSED(instance); @@ -184,6 +192,7 @@ static const struct serialPortVTable usbVTable[] = { .serialSetBaudRate = usbVcpSetBaudRate, .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, .setMode = usbVcpSetMode, + .setOptions = usbVcpSetOptions, .isConnected = usbVcpIsConnected, .writeBuf = usbVcpWriteBuf, .beginWrite = usbVcpBeginWrite, diff --git a/src/main/drivers/serial_usb_vcp_at32f43x.c b/src/main/drivers/serial_usb_vcp_at32f43x.c index 29b96d1a2b6..96b283ec363 100644 --- a/src/main/drivers/serial_usb_vcp_at32f43x.c +++ b/src/main/drivers/serial_usb_vcp_at32f43x.c @@ -308,6 +308,12 @@ static void usbVcpSetMode(serialPort_t *instance, portMode_t mode) UNUSED(mode); } +static void usbVcpSetOptions(serialPort_t *instance, portOptions_t options) +{ + UNUSED(instance); + UNUSED(options); +} + static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance) { UNUSED(instance); @@ -434,6 +440,7 @@ static const struct serialPortVTable usbVTable[] = { .serialSetBaudRate = usbVcpSetBaudRate, .isSerialTransmitBufferEmpty = isUsbVcpTransmitBufferEmpty, .setMode = usbVcpSetMode, + .setOptions = usbVcpSetOptions, .isConnected = usbVcpIsConnected, .writeBuf = usbVcpWriteBuf, .beginWrite = usbVcpBeginWrite, diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 0ea43fd0ce7..b9cc2a993b9 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -913,6 +913,42 @@ static void cliSerial(char *cmdline) } #ifdef USE_SERIAL_PASSTHROUGH + +portOptions_t constructPortOptions(char *options) { + if (strlen(options) != 3 || options[0] != '8') { + // Invalid format + return -1; + } + + portOptions_t result = 0; + + switch (options[1]) { + case 'N': + result |= SERIAL_PARITY_NO; + break; + case 'E': + result |= SERIAL_PARITY_EVEN; + break; + default: + // Invalid format + return -1; + } + + switch (options[2]) { + case '1': + result |= SERIAL_STOPBITS_1; + break; + case '2': + result |= SERIAL_STOPBITS_2; + break; + default: + // Invalid format + return -1; + } + + return result; +} + static void cliSerialPassthrough(char *cmdline) { char * saveptr; @@ -925,6 +961,7 @@ static void cliSerialPassthrough(char *cmdline) int id = -1; uint32_t baud = 0; unsigned mode = 0; + portOptions_t options = SERIAL_NOT_INVERTED; char* tok = strtok_r(cmdline, " ", &saveptr); int index = 0; @@ -942,6 +979,9 @@ static void cliSerialPassthrough(char *cmdline) if (strstr(tok, "tx") || strstr(tok, "TX")) mode |= MODE_TX; break; + case 3: + options |= constructPortOptions(tok); + break; } index++; tok = strtok_r(NULL, " ", &saveptr); @@ -959,7 +999,7 @@ static void cliSerialPassthrough(char *cmdline) passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL, NULL, baud, mode, - SERIAL_NOT_INVERTED); + options); if (!passThroughPort) { tfp_printf("Port %d could not be opened.\r\n", id); return; @@ -975,6 +1015,11 @@ static void cliSerialPassthrough(char *cmdline) passThroughPort->mode, mode); serialSetMode(passThroughPort, mode); } + if (options && passThroughPort->options != options) { + tfp_printf("Adjusting options from %d to %d.\r\n", + passThroughPort->options, options); + serialSetOptions(passThroughPort, options); + } // If this port has a rx callback associated we need to remove it now. // Otherwise no data will be pushed in the serial port buffer! if (passThroughPort->rxCallback) { @@ -4514,7 +4559,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave), CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial), #ifdef USE_SERIAL_PASSTHROUGH - CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", " [baud] [mode] : passthrough to serial", cliSerialPassthrough), + CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", " [baud] [mode] [options]: passthrough to serial", cliSerialPassthrough), #endif CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo), #ifdef USE_PROGRAMMING_FRAMEWORK From 957f23d5ddf300de7f587b8f4e20d604aa1c0f0a Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 1 Aug 2024 11:45:42 +0100 Subject: [PATCH 146/212] only BBL log servos defined in the mixer (#10267) * only BBL log servos defined in the mixer * address gcc13/gcc14/arm/intel GCC type mismatch --- src/main/blackbox/blackbox.c | 64 +++++++++++++++++--------- src/main/blackbox/blackbox_fielddefs.h | 19 ++++++++ 2 files changed, 62 insertions(+), 21 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 5a72d323b09..8c37ee3cb29 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -334,24 +334,24 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"motor", 7, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)}, /* servos */ - {"servo", 0, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 1, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 2, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 3, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 4, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 6, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 7, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 8, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 9, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 10, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 11, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 12, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 13, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, - {"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 0, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_1)}, + {"servo", 1, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_2)}, + {"servo", 2, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_3)}, + {"servo", 3, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_4)}, + {"servo", 4, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_5)}, + {"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_6)}, + {"servo", 6, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_7)}, + {"servo", 7, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_8)}, + {"servo", 8, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_9)}, + {"servo", 9, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_10)}, + {"servo", 10, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_11)}, + {"servo", 11, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_12)}, + {"servo", 12, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_13)}, + {"servo", 13, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_14)}, + {"servo", 14, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_15)}, + {"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_16)}, + {"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_17)}, + {"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)}, {"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, {"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, @@ -656,6 +656,26 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_SERVOS: return isMixerUsingServos(); + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18: + return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1); + case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2: @@ -955,7 +975,8 @@ static void writeIntraframe(void) } if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SERVOS)) { - for (int x = 0; x < MAX_SUPPORTED_SERVOS; x++) { + const int servoCount = getServoCount(); + for (int x = 0; x < servoCount; x++) { //Assume that servos spends most of its time around the center blackboxWriteSignedVB(blackboxCurrent->servo[x] - 1500); } @@ -1214,7 +1235,7 @@ static void writeInterframe(void) } if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SERVOS)) { - blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS); + blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), getServoCount()); } blackboxWriteSignedVB(blackboxCurrent->navState - blackboxLast->navState); @@ -1682,7 +1703,8 @@ static void loadMainState(timeUs_t currentTimeUs) blackboxCurrent->rssi = getRSSI(); - for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + const int servoCount = getServoCount(); + for (int i = 0; i < servoCount; i++) { blackboxCurrent->servo[i] = servo[i]; } diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 1e5615e3ec4..63a951d407c 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -33,7 +33,26 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8, + FLIGHT_LOG_FIELD_CONDITION_SERVOS, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18, FLIGHT_LOG_FIELD_CONDITION_MAG, FLIGHT_LOG_FIELD_CONDITION_BARO, From b347a48f7157beda78e2d2dfd198e1e0ef32f1db Mon Sep 17 00:00:00 2001 From: b14ckyy Date: Thu, 1 Aug 2024 17:33:10 +0200 Subject: [PATCH 147/212] Reset Mission start if RESUME is used and shorter mission is uploaded --- src/main/navigation/navigation.c | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 82452256a51..e43eb9d8534 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3703,7 +3703,8 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) setDesiredPosition(&wpPos.pos, DEGREES_TO_CENTIDEGREES(wpData->p1), waypointUpdateFlags); } // WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission - else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS)) { // && !ARMING_FLAG(ARMED) + else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !FLIGHT_MODE(NAV_WP_MODE)) { + // WP upload is not allowed why WP mode is active if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) static int8_t nonGeoWaypointCount = 0; @@ -3725,6 +3726,10 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) posControl.geoWaypointCount = posControl.waypointCount - nonGeoWaypointCount; if (posControl.waypointListValid) { nonGeoWaypointCount = 0; + // If active WP index is bigger than total mission WP number, reset active WP index (Mission Upload mid flight with interrupted mission) if RESUME is enabled + if (posControl.activeWaypointIndex > posControl.waypointCount) { + posControl.activeWaypointIndex = 0; + } } } } From 592ea06d89afeb653d5f12a14b29f58b822bd4ca Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 18:33:46 +0200 Subject: [PATCH 148/212] Working support for 26(34) channels sbus2 rc (Futaba FASSTest) --- src/main/rx/rx.h | 6 +--- src/main/rx/sbus.c | 66 +++++++++++++++++++------------------ src/main/rx/sbus.h | 1 + src/main/rx/sbus_channels.c | 25 +++++++------- src/main/rx/sbus_channels.h | 7 ++-- 5 files changed, 53 insertions(+), 52 deletions(-) diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 9e4816ec64c..c841838a5ea 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -84,11 +84,7 @@ typedef enum { SERIALRX_SBUS2, } rxSerialReceiverType_e; -#ifdef USE_24CHANNELS -#define MAX_SUPPORTED_RC_CHANNEL_COUNT 26 -#else -#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18 -#endif +#define MAX_SUPPORTED_RC_CHANNEL_COUNT 34 #define NON_AUX_CHANNEL_COUNT 4 #define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 70427932493..40de5d3bc2e 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -54,14 +54,14 @@ typedef enum { STATE_SBUS_SYNC = 0, STATE_SBUS_PAYLOAD, - STATE_SBUS26_PAYLOAD_LOW, - STATE_SBUS26_PAYLOAD_HIGH, + STATE_SBUS26_PAYLOAD, STATE_SBUS_WAIT_SYNC } sbusDecoderState_e; typedef struct sbusFrameData_s { sbusDecoderState_e state; volatile sbusFrame_t frame; + volatile sbusFrame_t frameHigh; volatile bool frameDone; volatile bool is26channels; uint8_t buffer[SBUS_FRAME_SIZE]; @@ -82,25 +82,23 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->lastActivityTimeUs = currentTimeUs; // Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire - if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { + if (timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { + sbusFrameData->state = STATE_SBUS_SYNC; + } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= 300) { + // payload is pausing too long, possible if some telemetry have been sent between frames sbusFrameData->state = STATE_SBUS_SYNC; } switch (sbusFrameData->state) { case STATE_SBUS_SYNC: - // Ignore non 26 channel packets - if (c == SBUS_FRAME_BEGIN_BYTE && !sbusFrameData->is26channels) { + if (c == SBUS_FRAME_BEGIN_BYTE) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if (c == SBUS26_FRAME0_BEGIN_BYTE) { - sbusFrameData->position = 0; - sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; - sbusFrameData->state = STATE_SBUS26_PAYLOAD_LOW; - } else if (c == SBUS26_FRAME1_BEGIN_BYTE) { + } else if ((uint8_t)c == SBUS26_FRAME_BEGIN_BYTE || c == 0xF2 || c == 0x2c) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; - sbusFrameData->state = STATE_SBUS26_PAYLOAD_HIGH; + sbusFrameData->state = STATE_SBUS26_PAYLOAD; } break; @@ -127,7 +125,6 @@ static void sbusDataReceive(uint16_t c, void *data) frameTime = -1; } - frameValid = true; sbusFrameData->state = STATE_SBUS_WAIT_SYNC; break; @@ -146,8 +143,7 @@ static void sbusDataReceive(uint16_t c, void *data) } break; - case STATE_SBUS26_PAYLOAD_LOW: - case STATE_SBUS26_PAYLOAD_HIGH: + case STATE_SBUS26_PAYLOAD: sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; if (sbusFrameData->position == SBUS_FRAME_SIZE) { @@ -156,38 +152,40 @@ static void sbusDataReceive(uint16_t c, void *data) // Do some sanity check switch (frame->endByte) { - case 0x20: // S.BUS 2 telemetry page 1 - case 0x24: // S.BUS 2 telemetry page 2 - case 0x28: // S.BUS 2 telemetry page 3 - case 0x2C: // S.BUS 2 telemetry page 4 - if (frame->syncByte == SBUS26_FRAME1_BEGIN_BYTE) { - sbus2ActiveTelemetryPage = (frame->endByte >> 2) & 0x3; - frameTime = currentTimeUs; - } - + case 0x00: + case 0x04: // S.BUS 2 telemetry page 1 + case 0x14: // S.BUS 2 telemetry page 2 + case 0x24: // S.BUS 2 telemetry page 3 + case 0x34: // S.BUS 2 telemetry page 4 + frameTime = -1; // ignore this one, as you can't fit telemetry between this and the next frame. frameValid = true; - sbusFrameData->state = STATE_SBUS_WAIT_SYNC; + sbusFrameData->state = STATE_SBUS_SYNC; // Next piece of data should be a sync byte break; default: // Failed end marker + frameValid = false; sbusFrameData->state = STATE_SBUS_WAIT_SYNC; break; } // Frame seems sane, pass data to decoder if (!sbusFrameData->frameDone && frameValid) { - memcpy((void *)&sbusFrameData->frame, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE); + memcpy((void *)&sbusFrameData->frameHigh, (void *)&sbusFrameData->buffer[0], SBUS_FRAME_SIZE); sbusFrameData->frameDone = true; sbusFrameData->is26channels = true; } } break; - - case STATE_SBUS_WAIT_SYNC: // Stay at this state and do nothing. Exit will be handled before byte is processed if the // inter-frame gap is long enough + if (c == SBUS26_FRAME_BEGIN_BYTE || c == 0xF2 || c == 0x2c) { + sbusFrameData->position = 0; + sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; + sbusFrameData->state = STATE_SBUS26_PAYLOAD; + } + break; } } @@ -200,16 +198,20 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) return RX_FRAME_PENDING; } + uint8_t retValue = 0; // Decode channel data and store return value - const uint8_t retValue = sbusFrameData->is26channels ? - sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, (sbusFrameData->frame.syncByte == SBUS26_FRAME1_BEGIN_BYTE)) : - sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels); + if (sbusFrameData->is26channels) + { + retValue = sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels, false); + retValue |= sbus26ChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frameHigh.channels, true); + + } else { + retValue = sbusChannelsDecode(rxRuntimeConfig, (void *)&sbusFrameData->frame.channels); + } // Reset the frameDone flag - tell ISR that we're ready to receive next frame sbusFrameData->frameDone = false; - //taskSendSbus2Telemetry(micros()); - // Calculate "virtual link quality based on packet loss metric" if (retValue & RX_FRAME_COMPLETE) { lqTrackerAccumulate(rxRuntimeConfig->lqTracker, ((retValue & RX_FRAME_DROPPED) || (retValue & RX_FRAME_FAILSAFE)) ? 0 : RSSI_MAX_VALUE); diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index aa550b618e1..810b577693e 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -18,6 +18,7 @@ #pragma once #define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case +#define SBUS_MIN_SYNC_DELAY_US MS2US(2) // 2ms #include "rx/rx.h" diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index 60f10737996..ebc5035220f 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -26,6 +26,8 @@ #include "common/utils.h" #include "common/maths.h" +#include "build/debug.h" + #include "rx/sbus_channels.h" @@ -55,17 +57,18 @@ uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChann sbusChannelData[14 + offset] = channels->chan14; sbusChannelData[15 + offset] = channels->chan15; - offset = highChannels ? 0 : 2; - if (channels->flags & SBUS_FLAG_CHANNEL_DG1) { - sbusChannelData[32 + offset] = SBUS_DIGITAL_CHANNEL_MAX; - } else { - sbusChannelData[32 + offset] = SBUS_DIGITAL_CHANNEL_MIN; - } - - if (channels->flags & SBUS_FLAG_CHANNEL_DG2) { - sbusChannelData[33 + offset] = SBUS_DIGITAL_CHANNEL_MAX; - } else { - sbusChannelData[33 + offset] = SBUS_DIGITAL_CHANNEL_MIN; + if (!highChannels) { + if (channels->flags & SBUS_FLAG_CHANNEL_DG1) { + sbusChannelData[32] = SBUS_DIGITAL_CHANNEL_MAX; + } else { + sbusChannelData[32] = SBUS_DIGITAL_CHANNEL_MIN; + } + + if (channels->flags & SBUS_FLAG_CHANNEL_DG2) { + sbusChannelData[33] = SBUS_DIGITAL_CHANNEL_MAX; + } else { + sbusChannelData[33] = SBUS_DIGITAL_CHANNEL_MIN; + } } uint8_t ret = 0; diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index d8070704052..4ff065f8d25 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -20,7 +20,7 @@ #include #include "rx/rx.h" -#define SBUS_MAX_CHANNEL 36 +#define SBUS_MAX_CHANNEL 34 #define SBUS_FLAG_CHANNEL_DG1 (1 << 0) #define SBUS_FLAG_CHANNEL_DG2 (1 << 1) @@ -30,9 +30,8 @@ #define SBUS_CHANNEL_DATA_LENGTH sizeof(sbusChannels_t) #define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2) -#define SBUS_FRAME_BEGIN_BYTE 0x0F -#define SBUS26_FRAME0_BEGIN_BYTE 0xF4 -#define SBUS26_FRAME1_BEGIN_BYTE 0xF0 +#define SBUS_FRAME_BEGIN_BYTE ((uint8_t)0x0F) +#define SBUS26_FRAME_BEGIN_BYTE ((uint8_t)0x2F) #define SBUS_BAUDRATE 100000 #define SBUS_BAUDRATE_FAST 200000 From e0ea833e2de32baf4be230c3eeee11544db505fe Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 18:49:28 +0200 Subject: [PATCH 149/212] Adding more servos --- src/main/blackbox/blackbox.c | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 5a72d323b09..80d0d67a4da 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -352,6 +352,23 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, + {"servo", 34, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(SERVOS)}, {"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, {"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, From 2722fb8f9c235f8caedfab9836fe1cf0cccca908 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 18:53:41 +0200 Subject: [PATCH 150/212] Cleanup and blackbox changes --- src/main/flight/servos.h | 4 +--- src/main/rx/sbus.c | 2 +- src/main/rx/sbus_channels.c | 8 +++----- 3 files changed, 5 insertions(+), 9 deletions(-) diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 5a161d6e4aa..79ab18caa36 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -20,7 +20,7 @@ #include "config/parameter_group.h" #include "programming/logic_condition.h" -#define MAX_SUPPORTED_SERVOS 36 +#define MAX_SUPPORTED_SERVOS 34 // These must be consecutive typedef enum { @@ -85,8 +85,6 @@ typedef enum { INPUT_RC_CH32 = 57, INPUT_RC_CH33 = 58, INPUT_RC_CH34 = 59, - INPUT_RC_CH35 = 60, - INPUT_RC_CH36 = 61, #endif INPUT_SOURCE_COUNT } inputSource_e; diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 40de5d3bc2e..1549ba74a8b 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -95,7 +95,7 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if ((uint8_t)c == SBUS26_FRAME_BEGIN_BYTE || c == 0xF2 || c == 0x2c) { + } else if ((uint8_t)c == SBUS26_FRAME_BEGIN_BYTE) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS26_PAYLOAD; diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index ebc5035220f..4794df2f7db 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -71,20 +71,18 @@ uint8_t sbus26ChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChann } } - uint8_t ret = 0; - if (channels->flags & SBUS_FLAG_FAILSAFE_ACTIVE) { // internal failsafe enabled and rx failsafe flag set // RX *should* still be sending valid channel data, so use it. - ret = RX_FRAME_FAILSAFE; + return RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE; } if (channels->flags & SBUS_FLAG_SIGNAL_LOSS) { // The received data is a repeat of the last valid data so can be considered complete. - ret = RX_FRAME_DROPPED; + return RX_FRAME_COMPLETE | RX_FRAME_DROPPED; } - return ret | (highChannels ? RX_FRAME_COMPLETE : RX_FRAME_PENDING); + return RX_FRAME_COMPLETE; } uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels) From fc8e4c1247b790eb854cdc33f3ef5b0c3aff9562 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 18:59:02 +0200 Subject: [PATCH 151/212] More blackbox changes that were missed --- src/main/blackbox/blackbox_fielddefs.h | 16 ++++++++++++++++ src/main/drivers/pwm_mapping.h | 2 +- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 63a951d407c..43d9542dad5 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -53,6 +53,22 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_27, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_28, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_29, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_30, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_31, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33, + FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34, FLIGHT_LOG_FIELD_CONDITION_MAG, FLIGHT_LOG_FIELD_CONDITION_BARO, diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 161735a4431..9b774bfac9d 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -28,7 +28,7 @@ #define MAX_MOTORS 12 #endif -#define MAX_SERVOS 36 +#define MAX_SERVOS 34 #define PWM_TIMER_HZ 1000000 From 4b140e476d17fa07c02341e3f50abc2a404ffd3c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 19:05:28 +0200 Subject: [PATCH 152/212] Limit servo count in blackbox to 26. I will deal with size 64bit limit on conditions later. --- src/main/blackbox/blackbox.c | 24 +++++++++++++++++++++++- src/main/blackbox/blackbox_fielddefs.h | 2 ++ 2 files changed, 25 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index fc88ac12bd2..ebb4f72a497 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -360,6 +360,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)}, {"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)}, {"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)}, + /* {"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)}, {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)}, {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_28)}, @@ -369,6 +370,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)}, {"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)}, {"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)}, + */ {"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, {"navFlags", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, @@ -691,7 +693,27 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18: - return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1); + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26: + /* + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_27: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_28: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_29: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_30: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_31: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_35: + case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_36: + */ + return ((FlightLogFieldCondition)MIN(getServoCount(), 26) >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1); case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 43d9542dad5..17595157dd2 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -61,6 +61,7 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26, + /* FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_27, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_28, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_29, @@ -69,6 +70,7 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33, FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34, + */ FLIGHT_LOG_FIELD_CONDITION_MAG, FLIGHT_LOG_FIELD_CONDITION_BARO, From 265cd57c20dc68ed50e9c7fb8e312cdfbf48112b Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 1 Aug 2024 18:10:50 +0100 Subject: [PATCH 153/212] add SERVOS to blackbox optional fields list (#10272) --- src/main/blackbox/blackbox.c | 9 +++++---- src/main/blackbox/blackbox.h | 3 ++- src/main/fc/cli.c | 17 +++++++++-------- 3 files changed, 16 insertions(+), 13 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8c37ee3cb29..11a23748c4f 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -99,7 +99,7 @@ #define BLACKBOX_INVERTED_CARD_DETECTION 0 #endif -PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 3); PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, .device = DEFAULT_BLACKBOX_DEVICE, @@ -108,7 +108,8 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, .invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION, .includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS | BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE | - BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND | BLACKBOX_FEATURE_MOTORS, + BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND | + BLACKBOX_FEATURE_MOTORS | BLACKBOX_FEATURE_SERVOS, ); void blackboxIncludeFlagSet(uint32_t mask) @@ -654,7 +655,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) return (getMotorCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_MOTORS); case FLIGHT_LOG_FIELD_CONDITION_SERVOS: - return isMixerUsingServos(); + return blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS) && isMixerUsingServos(); case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2: @@ -674,7 +675,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18: - return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1); + return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS); case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: diff --git a/src/main/blackbox/blackbox.h b/src/main/blackbox/blackbox.h index ea7482cbcd5..a329c11df12 100644 --- a/src/main/blackbox/blackbox.h +++ b/src/main/blackbox/blackbox.h @@ -35,6 +35,7 @@ typedef enum { BLACKBOX_FEATURE_GYRO_PEAKS_ROLL = 1 << 10, BLACKBOX_FEATURE_GYRO_PEAKS_PITCH = 1 << 11, BLACKBOX_FEATURE_GYRO_PEAKS_YAW = 1 << 12, + BLACKBOX_FEATURE_SERVOS = 1 << 13, } blackboxFeatureMask_e; typedef struct blackboxConfig_s { uint16_t rate_num; @@ -55,4 +56,4 @@ void blackboxFinish(void); bool blackboxMayEditConfig(void); void blackboxIncludeFlagSet(uint32_t mask); void blackboxIncludeFlagClear(uint32_t mask); -bool blackboxIncludeFlag(uint32_t mask); \ No newline at end of file +bool blackboxIncludeFlag(uint32_t mask); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 0ea43fd0ce7..32210d6ceee 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -183,6 +183,7 @@ static const char * const blackboxIncludeFlagNames[] = { "PEAKS_R", "PEAKS_P", "PEAKS_Y", + "SERVOS", NULL }; #endif @@ -1087,7 +1088,7 @@ static void cliAdjustmentRange(char *cmdline) } static void printMotorMix(uint8_t dumpMask, const motorMixer_t *primaryMotorMixer, const motorMixer_t *defaultprimaryMotorMixer) -{ +{ const char *format = "mmix %d %s %s %s %s"; char buf0[FTOA_BUFFER_SIZE]; char buf1[FTOA_BUFFER_SIZE]; @@ -1351,7 +1352,7 @@ static void cliTempSensor(char *cmdline) #endif #ifdef USE_FW_AUTOLAND -static void printFwAutolandApproach(uint8_t dumpMask, const navFwAutolandApproach_t *navFwAutolandApproach, const navFwAutolandApproach_t *defaultFwAutolandApproach) +static void printFwAutolandApproach(uint8_t dumpMask, const navFwAutolandApproach_t *navFwAutolandApproach, const navFwAutolandApproach_t *defaultFwAutolandApproach) { const char *format = "fwapproach %u %d %d %u %d %d %u"; for (uint8_t i = 0; i < MAX_FW_LAND_APPOACH_SETTINGS; i++) { @@ -1398,7 +1399,7 @@ static void cliFwAutolandApproach(char * cmdline) if ((ptr = nextArg(ptr))) { landDirection = fastA2I(ptr); - + if (landDirection != 0 && landDirection != 1) { cliShowParseError(); return; @@ -1428,7 +1429,7 @@ static void cliFwAutolandApproach(char * cmdline) validArgumentCount++; } - + if ((ptr = nextArg(ptr))) { isSeaLevelRef = fastA2I(ptr); validArgumentCount++; @@ -1842,7 +1843,7 @@ static void cliLedPinPWM(char *cmdline) if (isEmpty(cmdline)) { ledPinStopPWM(); cliPrintLine("PWM stopped"); - } else { + } else { i = fastA2I(cmdline); ledPinStartPWM(i); cliPrintLinef("PWM started: %d%%",i); @@ -3739,8 +3740,8 @@ static void cliStatus(char *cmdline) #if defined(AT32F43x) cliPrintLine("AT32 system clocks:"); crm_clocks_freq_type clocks; - crm_clocks_freq_get(&clocks); - + crm_clocks_freq_get(&clocks); + cliPrintLinef(" SYSCLK = %d MHz", clocks.sclk_freq / 1000000); cliPrintLinef(" ABH = %d MHz", clocks.ahb_freq / 1000000); cliPrintLinef(" ABP1 = %d MHz", clocks.apb1_freq / 1000000); @@ -4382,7 +4383,7 @@ static const char *_ubloxGetQuality(uint8_t quality) case UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC: return "Code locked and time sync"; case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC: case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2: - case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3: + case UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3: return "Code and carrier locked and time sync"; default: return "Unknown"; } From ed4be684a2ab44acc2e1dcf0d7c22d99fcf8756d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 19:37:40 +0200 Subject: [PATCH 154/212] Better comments --- src/main/rx/sbus.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 1549ba74a8b..21aef81e4b2 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -85,7 +85,7 @@ static void sbusDataReceive(uint16_t c, void *data) if (timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { sbusFrameData->state = STATE_SBUS_SYNC; } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= 300) { - // payload is pausing too long, possible if some telemetry have been sent between frames + // payload is pausing too long, possible if some telemetry have been sent between frames, or false positves mid frame sbusFrameData->state = STATE_SBUS_SYNC; } From ad9e074f1ee454a915b0dd752396800f1769e9d6 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 21:32:42 +0200 Subject: [PATCH 155/212] Update blackbox.c --- src/main/blackbox/blackbox.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 400ad17762a..1222af19cd8 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -711,8 +711,6 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_32: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34: - case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_35: - case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_36: */ return ((FlightLogFieldCondition)MIN(getServoCount(), 26) >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS); From ac03ee3c162115db018f76dba876033728aa29ae Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 22:05:13 +0200 Subject: [PATCH 156/212] Allow number of servos exceed pwm outputs, if servo protocol is sbus_pwm --- src/main/drivers/pwm_mapping.c | 11 +++++++++-- src/main/drivers/pwm_output.c | 2 +- src/main/io/servo_sbus.h | 2 ++ 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 5ed17d7bb9a..d631243790a 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -42,6 +42,7 @@ #include "sensors/rangefinder.h" #include "io/serial.h" +#include "io/servo_sbus.h" enum { MAP_TO_NONE, @@ -442,15 +443,21 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs) return; } + // If mixer requests more servos than we have timer outputs - throw an error - if (servoCount > timOutputs->maxTimServoCount) { + uint16_t maxServos = timOutputs->maxTimServoCount; + if(servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM) { + maxServos = MAX(SERVO_SBUS_MAX_SERVOS, timOutputs->maxTimServoCount); + } + + if (servoCount > maxServos) { pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS; LOG_ERROR(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount); return; } // Configure individual servo outputs - for (int idx = 0; idx < servoCount; idx++) { + for (int idx = 0; idx < MIN(servoCount, timOutputs->maxTimServoCount); idx++) { const timerHardware_t *timHw = timOutputs->timServos[idx]; if (!pwmServoConfig(timHw, idx, servoConfig()->servoPwmRate, servoConfig()->servoCenterPulse, feature(FEATURE_PWM_OUTPUT_ENABLE))) { diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index faa9cd373d9..619f4b95db5 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -638,7 +638,7 @@ ioTag_t pwmGetMotorPinTag(int motorIndex) static void pwmServoWriteStandard(uint8_t index, uint16_t value) { - if (servos[index]) { + if (index < MAX_SERVOS && servos[index]) { *servos[index]->ccr = value; } } diff --git a/src/main/io/servo_sbus.h b/src/main/io/servo_sbus.h index 0dcc14ac8de..2def87b7bb7 100644 --- a/src/main/io/servo_sbus.h +++ b/src/main/io/servo_sbus.h @@ -24,6 +24,8 @@ #pragma once +#define SERVO_SBUS_MAX_SERVOS 18 + bool sbusServoInitialize(void); void sbusServoUpdate(uint8_t index, uint16_t value); void sbusServoSendUpdate(void); From 8f55d6595dcb37a2f1e6868305af8aba5998486e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 1 Aug 2024 22:10:57 +0200 Subject: [PATCH 157/212] Build fixes --- src/main/drivers/pwm_mapping.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 08123130f2c..3f08d9b500a 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -21,6 +21,7 @@ #include "flight/mixer.h" #include "flight/mixer_profile.h" #include "flight/servos.h" +#include "common/maths.h" #if defined(TARGET_MOTOR_COUNT) #define MAX_MOTORS TARGET_MOTOR_COUNT From f7a5af165a8e8f6baad30ba5c1c4f66045310422 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 09:55:48 +0200 Subject: [PATCH 158/212] Rename frame byte Remove SBUS26 name, as it will likely have other modes in the future. --- src/main/rx/sbus_channels.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index 4ff065f8d25..a0276ac005c 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -31,7 +31,7 @@ #define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2) #define SBUS_FRAME_BEGIN_BYTE ((uint8_t)0x0F) -#define SBUS26_FRAME_BEGIN_BYTE ((uint8_t)0x2F) +#define SBUS2_HIGHFRAME_BEGIN_BYTE ((uint8_t)0x2F) #define SBUS_BAUDRATE 100000 #define SBUS_BAUDRATE_FAST 200000 From 124a0d31e5a50eadde02c8a045320d0aca4be5f2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 09:58:34 +0200 Subject: [PATCH 159/212] Continue sync byte renaming --- src/main/rx/sbus.c | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index 21aef81e4b2..a7ba93456f4 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -95,7 +95,7 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if ((uint8_t)c == SBUS26_FRAME_BEGIN_BYTE) { + } else if ((uint8_t)c == SBUS2_HIGHFRAME_BEGIN_BYTE) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS26_PAYLOAD; @@ -180,12 +180,6 @@ static void sbusDataReceive(uint16_t c, void *data) case STATE_SBUS_WAIT_SYNC: // Stay at this state and do nothing. Exit will be handled before byte is processed if the // inter-frame gap is long enough - if (c == SBUS26_FRAME_BEGIN_BYTE || c == 0xF2 || c == 0x2c) { - sbusFrameData->position = 0; - sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; - sbusFrameData->state = STATE_SBUS26_PAYLOAD; - } - break; } } From f5e46e88326a6dc71be5cc2beba12c513d292c5d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 12:20:55 +0200 Subject: [PATCH 160/212] Update pwm_mapping.h --- src/main/drivers/pwm_mapping.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 9b774bfac9d..08123130f2c 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -28,7 +28,7 @@ #define MAX_MOTORS 12 #endif -#define MAX_SERVOS 34 +#define MAX_SERVOS 18 #define PWM_TIMER_HZ 1000000 From aec8276c9b5ed93eef50abfca45c3cc31ec051a3 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 12:23:07 +0200 Subject: [PATCH 161/212] Update servos.h to match pwm_mapping.h --- src/main/flight/servos.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 79ab18caa36..634c7b0cd58 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -20,7 +20,7 @@ #include "config/parameter_group.h" #include "programming/logic_condition.h" -#define MAX_SUPPORTED_SERVOS 34 +#define MAX_SUPPORTED_SERVOS 18 // These must be consecutive typedef enum { From adf73f1338b07f37b11fb1a87be3062d96d37417 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 12:54:14 +0200 Subject: [PATCH 162/212] before merging master --- src/main/drivers/pwm_mapping.h | 2 +- src/main/flight/servos.h | 4 +--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 47311768aec..3f08d9b500a 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -29,7 +29,7 @@ #define MAX_MOTORS 12 #endif -#define MAX_SERVOS 34 +#define MAX_SERVOS 18 #define PWM_TIMER_HZ 1000000 diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 79ab18caa36..23ac3fda495 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -20,7 +20,7 @@ #include "config/parameter_group.h" #include "programming/logic_condition.h" -#define MAX_SUPPORTED_SERVOS 34 +#define MAX_SUPPORTED_SERVOS 18 // These must be consecutive typedef enum { @@ -68,7 +68,6 @@ typedef enum { INPUT_HEADTRACKER_ROLL = 41, INPUT_RC_CH17 = 42, INPUT_RC_CH18 = 43, -#ifdef USE_24CHANNELS INPUT_RC_CH19 = 44, INPUT_RC_CH20 = 45, INPUT_RC_CH21 = 46, @@ -85,7 +84,6 @@ typedef enum { INPUT_RC_CH32 = 57, INPUT_RC_CH33 = 58, INPUT_RC_CH34 = 59, -#endif INPUT_SOURCE_COUNT } inputSource_e; From d61d3524d0c949c69a6469ad8aa97d90ae7aa150 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 12:55:03 +0200 Subject: [PATCH 163/212] rename USE_24CHANELS to USE_34CHANNELS --- src/main/fc/rc_controls.h | 12 +++++++++++- src/main/flight/servos.c | 12 +++++++++++- src/main/rx/jetiexbus.c | 2 +- src/main/target/common.h | 2 +- 4 files changed, 24 insertions(+), 4 deletions(-) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 3705a29c3a1..f5b96f2d239 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -40,13 +40,23 @@ typedef enum rc_alias { AUX12, // 16 AUX13, // 17 AUX14, // 18 -#ifdef USE_24CHANNELS +#ifdef USE_34CHANNELS AUX15, // 19 AUX16, // 20 AUX17, // 21 AUX18, // 22 AUX19, // 23 AUX20, // 24 + AUX21, // 25 + AUX22, // 26 + AUX23, // 27 + AUX24, // 28 + AUX25, // 29 + AUX26, // 30 + AUX27, // 31 + AUX28, // 32 + AUX29, // 33 + AUX30, // 34 #endif } rc_alias_e; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 5ac98f78215..40711706e78 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -349,13 +349,23 @@ void servoMixer(float dT) input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12); input[INPUT_RC_CH17] = GET_RX_CHANNEL_INPUT(AUX13); input[INPUT_RC_CH18] = GET_RX_CHANNEL_INPUT(AUX14); -#ifdef USE_24CHANNELS +#ifdef USE_34CHANNELS input[INPUT_RC_CH19] = GET_RX_CHANNEL_INPUT(AUX15); input[INPUT_RC_CH20] = GET_RX_CHANNEL_INPUT(AUX16); input[INPUT_RC_CH21] = GET_RX_CHANNEL_INPUT(AUX17); input[INPUT_RC_CH22] = GET_RX_CHANNEL_INPUT(AUX18); input[INPUT_RC_CH23] = GET_RX_CHANNEL_INPUT(AUX19); input[INPUT_RC_CH24] = GET_RX_CHANNEL_INPUT(AUX20); + input[INPUT_RC_CH25] = GET_RX_CHANNEL_INPUT(AUX21); + input[INPUT_RC_CH26] = GET_RX_CHANNEL_INPUT(AUX22); + input[INPUT_RC_CH27] = GET_RX_CHANNEL_INPUT(AUX23); + input[INPUT_RC_CH28] = GET_RX_CHANNEL_INPUT(AUX24); + input[INPUT_RC_CH29] = GET_RX_CHANNEL_INPUT(AUX25); + input[INPUT_RC_CH30] = GET_RX_CHANNEL_INPUT(AUX26); + input[INPUT_RC_CH31] = GET_RX_CHANNEL_INPUT(AUX27); + input[INPUT_RC_CH32] = GET_RX_CHANNEL_INPUT(AUX28); + input[INPUT_RC_CH33] = GET_RX_CHANNEL_INPUT(AUX29); + input[INPUT_RC_CH34] = GET_RX_CHANNEL_INPUT(AUX30); #endif #undef GET_RX_CHANNEL_INPUT diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index 35564833994..9e3c04d2c12 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -64,7 +64,7 @@ #define JETIEXBUS_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) #define JETIEXBUS_MIN_FRAME_GAP 1000 -#ifdef USE_24CHANNELS +#ifdef USE_34CHANNELS #define JETIEXBUS_CHANNEL_COUNT 24 #else #define JETIEXBUS_CHANNEL_COUNT 16 diff --git a/src/main/target/common.h b/src/main/target/common.h index 51f1fbf6ea6..f7cc3f747ce 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -206,7 +206,7 @@ #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE -#define USE_24CHANNELS +#define USE_34CHANNELS #define MAX_MIXER_PROFILE_COUNT 2 #define USE_SMARTPORT_MASTER #elif !defined(STM32F7) From a863afadf06742559e06cc46187196f99395b7dd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 2 Aug 2024 15:58:54 +0200 Subject: [PATCH 164/212] Update pwm_mapping.c --- src/main/drivers/pwm_mapping.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index d631243790a..2d01127a504 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -446,7 +446,7 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs) // If mixer requests more servos than we have timer outputs - throw an error uint16_t maxServos = timOutputs->maxTimServoCount; - if(servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM) { + if (servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM) { maxServos = MAX(SERVO_SBUS_MAX_SERVOS, timOutputs->maxTimServoCount); } From cfa0892f9dca3fa3861a1ffdc193a4fbd297b130 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 4 Aug 2024 11:27:40 +0100 Subject: [PATCH 165/212] wp tracking improvement --- src/main/navigation/navigation_fixedwing.c | 41 +++++++++++----------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 71a7f99fc34..183c5a85269 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -401,33 +401,32 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta /* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */ if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - // courseVirtualCorrection initially used to determine current position relative to course line for later use int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); navCrossTrackError = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection))); - // tracking only active when certain distance and heading conditions are met - if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) { - int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.bearing - posControl.actualState.cog); - - // captureFactor adjusts distance/heading sensitivity balance when closing in on course line. - // Closing distance threashold based on speed and an assumed 1 second response time. - float captureFactor = navCrossTrackError < posControl.actualState.velXY ? constrainf(2.0f - ABS(courseHeadingError) / 500.0f, 0.0f, 2.0f) : 1.0f; - - // bias between reducing distance to course line and aligning with course heading adjusted by waypoint_tracking_accuracy - // initial courseCorrectionFactor based on distance to course line - float courseCorrectionFactor = constrainf(captureFactor * navCrossTrackError / (1000.0f * navConfig()->fw.wp_tracking_accuracy), 0.0f, 1.0f); - courseCorrectionFactor = courseVirtualCorrection < 0 ? -courseCorrectionFactor : courseCorrectionFactor; + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200.0f) { + static float crossTrackErrorRate; + if ((currentTimeUs - previousTimeMonitoringUpdate) >= HZ2US(NAV_FW_CONTROL_MONITORING_RATE)) { + static float previousCrossTrackError = 0.0f; + crossTrackErrorRate = 0.5f * (crossTrackErrorRate + (previousCrossTrackError - navCrossTrackError) / US2S(currentTimeUs - previousTimeMonitoringUpdate)); + previousCrossTrackError = navCrossTrackError; + } - // course heading alignment factor - float courseHeadingFactor = constrainf(courseHeadingError / 18000.0f, 0.0f, 1.0f); - courseHeadingFactor = courseHeadingError < 0 ? -courseHeadingFactor : courseHeadingFactor; + /* Apply basic adjustment to factor up virtualTargetBearing error based on navCrossTrackError */ + float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); + adjustmentFactor *= 1.0f + sq(navCrossTrackError / (navConfig()->fw.wp_tracking_accuracy * 500.0f)); - // final courseCorrectionFactor combining distance and heading factors - courseCorrectionFactor = constrainf(courseCorrectionFactor - courseHeadingFactor, -1.0f, 1.0f); + /* Apply additional fine adjustment based on speed of convergence to try and achieve arrival time of around 15s */ + float limit = constrainf(navCrossTrackError / 3.0f, 200.0f, 500.0f); + float rateFactor = limit; + if (crossTrackErrorRate > 0.0f) { + rateFactor = scaleRangef(navCrossTrackError / crossTrackErrorRate, 0.0f, 30.0f, -limit, limit); + } - // final courseVirtualCorrection value - courseVirtualCorrection = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle) * courseCorrectionFactor; - virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - courseVirtualCorrection); + /* Determine final adjusted virtualTargetBearing */ + uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle); + adjustmentFactor = constrainf(adjustmentFactor + rateFactor * SIGN(adjustmentFactor), -angleLimit, angleLimit); + virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor); } } From 42322663f644e1f134ec3ad21a48cbfada3a312f Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 4 Aug 2024 11:48:43 +0100 Subject: [PATCH 166/212] Update navigation_fixedwing.c --- src/main/navigation/navigation_fixedwing.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 183c5a85269..f762295d8b2 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -420,7 +420,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta float limit = constrainf(navCrossTrackError / 3.0f, 200.0f, 500.0f); float rateFactor = limit; if (crossTrackErrorRate > 0.0f) { - rateFactor = scaleRangef(navCrossTrackError / crossTrackErrorRate, 0.0f, 30.0f, -limit, limit); + rateFactor = constrainf(scaleRangef(navCrossTrackError / crossTrackErrorRate, 0, 30, -limit, limit), -limit, limit); } /* Determine final adjusted virtualTargetBearing */ From a53c3030d880af6d7a325beeed47afeec6c54c1a Mon Sep 17 00:00:00 2001 From: KY-S0ong <156529018+KY-S0ong@users.noreply.github.com> Date: Mon, 5 Aug 2024 16:35:01 -0400 Subject: [PATCH 167/212] Update USB Flashing.md --- docs/USB Flashing.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index 4b885ef02eb..e3bba4291b8 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -50,6 +50,15 @@ With the board connected and in bootloader mode (reset it by sending the charact * Select `STM32 BOOTLOADER` in the device list * Choose `WinUSB (v6.x.x.x)` in the right hand box +## Platoform: Mac-OS + +The Configuator devices can have a problem accesing USB devices on Mac-OS. This is ussaly solved by a cable change. + +* The official Apple USB-C to USB-C will not work no matter orentation. +* Make sure the cable you are using support data transfer + * For best results, use a USB-C to USB-A cable (And a dongle if your computer does not have an USB-A port) + * Dongle side pluged into the computer + ![Zadig Driver Procedure](assets/images/zadig-dfu.png) * Click Replace Driver From e8f9503d8f615bd20fbc6f304273f8db5287f64f Mon Sep 17 00:00:00 2001 From: KY-S0ong <156529018+KY-S0ong@users.noreply.github.com> Date: Mon, 5 Aug 2024 16:50:52 -0400 Subject: [PATCH 168/212] Update USB Flashing.md Adds instructions on how to use the Configurator on Mac-OS --- docs/USB Flashing.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index e3bba4291b8..b0fd876d9cf 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -52,7 +52,7 @@ With the board connected and in bootloader mode (reset it by sending the charact ## Platoform: Mac-OS -The Configuator devices can have a problem accesing USB devices on Mac-OS. This is ussaly solved by a cable change. +Configuator devices can have a problem accesing USB devices on Mac-OS. This is *ussaly* solved by a cable change. * The official Apple USB-C to USB-C will not work no matter orentation. * Make sure the cable you are using support data transfer From a548bc6165f4d5f7c830506e98ffbe4052faf7cd Mon Sep 17 00:00:00 2001 From: KY-S0ong <156529018+KY-S0ong@users.noreply.github.com> Date: Mon, 5 Aug 2024 16:54:53 -0400 Subject: [PATCH 169/212] Update USB Flashing.md Fixed some formatting. Still for Mac-OS help --- docs/USB Flashing.md | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index b0fd876d9cf..4981e95a043 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -49,6 +49,12 @@ With the board connected and in bootloader mode (reset it by sending the charact * Choose Options > List All Devices * Select `STM32 BOOTLOADER` in the device list * Choose `WinUSB (v6.x.x.x)` in the right hand box + +![Zadig Driver Procedure](assets/images/zadig-dfu.png) + +* Click Replace Driver +* Restart the Configurator (make sure it is completely closed, logout and login if unsure) +* Now the DFU device should be seen by Configurator ## Platoform: Mac-OS @@ -58,13 +64,6 @@ Configuator devices can have a problem accesing USB devices on Mac-OS. This is * * Make sure the cable you are using support data transfer * For best results, use a USB-C to USB-A cable (And a dongle if your computer does not have an USB-A port) * Dongle side pluged into the computer - -![Zadig Driver Procedure](assets/images/zadig-dfu.png) - -* Click Replace Driver -* Restart the Configurator (make sure it is completely closed, logout and login if unsure) -* Now the DFU device should be seen by Configurator - ## Using `dfu-util` From 70ecef84cb8168f26426def36b6308b9a3030228 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Mon, 5 Aug 2024 19:36:47 -0500 Subject: [PATCH 170/212] cli.c: Add reason for Navigation Unsafe to status --- src/main/fc/cli.c | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 7a3e1f1b78f..ee5cb289a94 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3894,6 +3894,24 @@ static void cliStatus(char *cmdline) cliPrintErrorLinef("Invalid setting: %s", buf); } } + +#if defined(USE_OSD) + if (armingFlags & ARMING_DISABLED_NAVIGATION_UNSAFE) { + navArmingBlocker_e reason = navigationIsBlockingArming(NULL); + if (reason & NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR) + cliPrintLinef(" %s", OSD_MSG_JUMP_WP_MISCONFIG); + if (reason & NAV_ARMING_BLOCKER_MISSING_GPS_FIX) { + cliPrintLinef(" %s", OSD_MSG_WAITING_GPS_FIX); + } else { + if (reason & NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE) + cliPrintLinef(" %s", OSD_MSG_DISABLE_NAV_FIRST); + if (reason & NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR) + cliPrintLinef(" FIRST WP TOO FAR"); + } + } +#endif + + #else cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS); #endif From c58c958e4916645c7e76fdf2c5fbc1f4c147cb8c Mon Sep 17 00:00:00 2001 From: flywoo Date: Wed, 7 Aug 2024 16:07:34 +0800 Subject: [PATCH 171/212] Add FLYWOOH743PRO Target --- src/main/target/FLYWOOH743PRO/CMakeLists.txt | 1 + src/main/target/FLYWOOH743PRO/config.c | 31 +++ src/main/target/FLYWOOH743PRO/target.c | 48 +++++ src/main/target/FLYWOOH743PRO/target.h | 189 +++++++++++++++++++ 4 files changed, 269 insertions(+) create mode 100644 src/main/target/FLYWOOH743PRO/CMakeLists.txt create mode 100644 src/main/target/FLYWOOH743PRO/config.c create mode 100644 src/main/target/FLYWOOH743PRO/target.c create mode 100644 src/main/target/FLYWOOH743PRO/target.h diff --git a/src/main/target/FLYWOOH743PRO/CMakeLists.txt b/src/main/target/FLYWOOH743PRO/CMakeLists.txt new file mode 100644 index 00000000000..0a1aaea5145 --- /dev/null +++ b/src/main/target/FLYWOOH743PRO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(FLYWOOH743PRO) diff --git a/src/main/target/FLYWOOH743PRO/config.c b/src/main/target/FLYWOOH743PRO/config.c new file mode 100644 index 00000000000..0f1fec5a816 --- /dev/null +++ b/src/main/target/FLYWOOH743PRO/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/FLYWOOH743PRO/target.c b/src/main/target/FLYWOOH743PRO/target.c new file mode 100644 index 00000000000..ef25c2f8eb9 --- /dev/null +++ b/src/main/target/FLYWOOH743PRO/target.c @@ -0,0 +1,48 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_1, DEVHW_ICM42605, ICM42605_1_SPI_BUS, ICM42605_1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_2, DEVHW_ICM42605, ICM42605_2_SPI_BUS, ICM42605_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 + DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOH743PRO/target.h b/src/main/target/FLYWOOH743PRO/target.h new file mode 100644 index 00000000000..47419dc78ff --- /dev/null +++ b/src/main/target/FLYWOOH743PRO/target.h @@ -0,0 +1,189 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FWH7" +#define USBD_PRODUCT_STRING "FLYWOOH743PRO" + +#define USE_TARGET_CONFIG + +#define LED0 PE3 +#define LED1 PE4 + +#define BEEPER PA15 +#define BEEPER_INVERTED + +// *************** IMU generic *********************** +#define USE_DUAL_GYRO +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_IMU_ICM42605 +// *************** SPI1 IMU0 ICM42605_1 **************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PD7 + +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_1_SPI_BUS BUS_SPI1 +#define ICM42605_1_CS_PIN PC15 + +// *************** SPI4 IMU1 ICM42605_2 ************** +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 + +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_2_SPI_BUS BUS_SPI4 +#define ICM42605_2_CS_PIN PE11 + +// *************** SPI2 OSD *********************** + #define USE_SPI_DEVICE_2 + #define SPI2_SCK_PIN PB13 + #define SPI2_MISO_PIN PB14 + #define SPI2_MOSI_PIN PB15 + + #define USE_MAX7456 + #define MAX7456_SPI_BUS BUS_SPI2 + #define MAX7456_CS_PIN PB12 + +// *************** SPI3 SPARE for external RM3100 *********** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_MAG_RM3100 +#define RM3100_CS_PIN PE2 //CS2 pad +#define RM3100_SPI_BUS BUS_SPI3 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define PITOT_I2C_BUS BUS_I2C2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 + +#define USE_UART4 +#define UART4_TX_PIN PB9 +#define UART4_RX_PIN PB8 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART6 + +// *************** SDIO SD BLACKBOX******************* +#define USE_SDCARD +#define USE_SDCARD_SDIO +#define SDCARD_SDIO_DEVICE SDIODEV_1 +#define SDCARD_SDIO_4BIT + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC0 //ADC123 VBAT1 +#define ADC_CHANNEL_2_PIN PC1 //ADC123 CURR1 +#define ADC_CHANNEL_3_PIN PC5 //ADC12 RSSI +#define ADC_CHANNEL_4_PIN PC4 //ADC12 AirS +#define ADC_CHANNEL_6_PIN PA7 //ADC12 CU2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PD10 // VTX power switcher +#define PINIO2_PIN PD11 // 2xCamera switcher + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 250 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 12 +#define USE_DSHOT +#define USE_ESC_SENSOR + From 0f04b7e98ef8bfdb576f0ffe59d1c4284ecff675 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 7 Aug 2024 23:40:14 +0200 Subject: [PATCH 172/212] Support SBUS2 FASSTest 12 channel short frame time --- src/main/fc/fc_tasks.c | 2 +- src/main/rx/sbus.c | 16 +++++++++++++--- src/main/rx/sbus.h | 3 ++- src/main/telemetry/sbus2.c | 6 +++++- 4 files changed, 21 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 107a0e732b6..afb880db526 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -439,7 +439,7 @@ void fcTasksInit(void) #endif #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_SBUS2) - setTaskEnabled(TASK_TELEMETRY_SBUS2,rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_SBUS2); + setTaskEnabled(TASK_TELEMETRY_SBUS2,feature(FEATURE_TELEMETRY) && rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_SBUS2); #endif #ifdef USE_ADAPTIVE_FILTER diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index a7ba93456f4..f08267eeb1d 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -71,6 +71,7 @@ typedef struct sbusFrameData_s { static uint8_t sbus2ActiveTelemetryPage = 0; static uint8_t sbus2ActiveTelemetrySlot = 0; +static uint8_t sbus2ShortFrameInterval = 0; timeUs_t frameTime = 0; // Receive ISR callback @@ -81,10 +82,16 @@ static void sbusDataReceive(uint16_t c, void *data) const timeDelta_t timeSinceLastByteUs = cmpTimeUs(currentTimeUs, sbusFrameData->lastActivityTimeUs); sbusFrameData->lastActivityTimeUs = currentTimeUs; + const int32_t syncInterval = sbus2ShortFrameInterval + ? ((6300 - SBUS_BYTE_TIME_US(25)) / 2) + : rxConfig()->sbusSyncInterval; + + // Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire - if (timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) { + if ((sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= syncInterval) + || (rxConfig()->serialrx_provider == SERIALRX_SBUS2 && timeSinceLastByteUs >= SBUS_BYTE_TIME_US(3))) { sbusFrameData->state = STATE_SBUS_SYNC; - } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= 300) { + } else if ((sbusFrameData->state == STATE_SBUS_PAYLOAD || sbusFrameData->state == STATE_SBUS26_PAYLOAD) && timeSinceLastByteUs >= SBUS_BYTE_TIME_US(3)) { // payload is pausing too long, possible if some telemetry have been sent between frames, or false positves mid frame sbusFrameData->state = STATE_SBUS_SYNC; } @@ -95,7 +102,7 @@ static void sbusDataReceive(uint16_t c, void *data) sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS_PAYLOAD; - } else if ((uint8_t)c == SBUS2_HIGHFRAME_BEGIN_BYTE) { + } else if (c == SBUS2_HIGHFRAME_BEGIN_BYTE) { sbusFrameData->position = 0; sbusFrameData->buffer[sbusFrameData->position++] = (uint8_t)c; sbusFrameData->state = STATE_SBUS26_PAYLOAD; @@ -113,12 +120,15 @@ static void sbusDataReceive(uint16_t c, void *data) switch (frame->endByte) { case 0x00: // This is S.BUS 1 case 0x04: // S.BUS 2 telemetry page 1 + case 0x08: // S.BUS 2 fast frame pace, not telemetry. case 0x14: // S.BUS 2 telemetry page 2 case 0x24: // S.BUS 2 telemetry page 3 case 0x34: // S.BUS 2 telemetry page 4 if(frame->endByte & 0x4) { sbus2ActiveTelemetryPage = (frame->endByte >> 4) & 0xF; frameTime = currentTimeUs; + } else if(frame->endByte == 0x08) { + sbus2ShortFrameInterval = 1; } else { sbus2ActiveTelemetryPage = 0; sbus2ActiveTelemetrySlot = 0; diff --git a/src/main/rx/sbus.h b/src/main/rx/sbus.h index 810b577693e..20ed82e2dae 100644 --- a/src/main/rx/sbus.h +++ b/src/main/rx/sbus.h @@ -18,13 +18,14 @@ #pragma once #define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case -#define SBUS_MIN_SYNC_DELAY_US MS2US(2) // 2ms #include "rx/rx.h" bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); bool sbusInitFast(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); +#define SBUS_BYTE_TIME_US(bytes) MS2US(10 * 12 * bytes) // 10us per bit * (1 start + 8 data + 1 parity + 2 stop) * number of bytes + #ifdef USE_TELEMETRY_SBUS2 uint8_t sbusGetCurrentTelemetryPage(void); uint8_t sbusGetCurrentTelemetryNextSlot(void); diff --git a/src/main/telemetry/sbus2.c b/src/main/telemetry/sbus2.c index dc5fb81d77d..1e800f2f098 100644 --- a/src/main/telemetry/sbus2.c +++ b/src/main/telemetry/sbus2.c @@ -25,6 +25,10 @@ #include "common/time.h" #include "common/axis.h" +#include "config/feature.h" + +#include "fc/config.h" + #include "telemetry/telemetry.h" #include "telemetry/sbus2.h" #include "telemetry/sbus2_sensors.h" @@ -164,7 +168,7 @@ void sbus2IncrementTelemetrySlot(timeUs_t currentTimeUs) FAST_CODE void taskSendSbus2Telemetry(timeUs_t currentTimeUs) { - if (!telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || + if (!feature(FEATURE_TELEMETRY) || !telemetrySharedPort || rxConfig()->receiverType != RX_TYPE_SERIAL || rxConfig()->serialrx_provider != SERIALRX_SBUS2) { return; } From b3da693c5a35f58c12b152f64bb3358c520eb3c0 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 8 Aug 2024 09:06:54 +0100 Subject: [PATCH 173/212] Improvements --- src/main/navigation/navigation_fixedwing.c | 26 ++++++++++++++-------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index f762295d8b2..0c49ad4fda7 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -401,14 +401,21 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta /* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */ if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); - navCrossTrackError = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection))); - - if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200.0f) { + fpVector3_t virtualCoursePoint; + virtualCoursePoint.x = posControl.activeWaypoint.pos.x - + posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + virtualCoursePoint.y = posControl.activeWaypoint.pos.y - + posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); + + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) { static float crossTrackErrorRate; - if ((currentTimeUs - previousTimeMonitoringUpdate) >= HZ2US(NAV_FW_CONTROL_MONITORING_RATE)) { + static timeUs_t previousCrossTrackErrorUpdateTime; + + if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(10)) { static float previousCrossTrackError = 0.0f; - crossTrackErrorRate = 0.5f * (crossTrackErrorRate + (previousCrossTrackError - navCrossTrackError) / US2S(currentTimeUs - previousTimeMonitoringUpdate)); + crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); + previousCrossTrackErrorUpdateTime = currentTimeUs; previousCrossTrackError = navCrossTrackError; } @@ -416,11 +423,12 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); adjustmentFactor *= 1.0f + sq(navCrossTrackError / (navConfig()->fw.wp_tracking_accuracy * 500.0f)); - /* Apply additional fine adjustment based on speed of convergence to try and achieve arrival time of around 15s */ - float limit = constrainf(navCrossTrackError / 3.0f, 200.0f, 500.0f); + /* Apply additional fine adjustment based on speed of convergence to achieve a convergence speed of around 2 m/s */ + float limit = constrainf((crossTrackErrorRate > 0.0f ? crossTrackErrorRate : 0.0f) + navCrossTrackError / 3.0f, 200.0f, posControl.actualState.velXY / 4.0f); float rateFactor = limit; if (crossTrackErrorRate > 0.0f) { - rateFactor = constrainf(scaleRangef(navCrossTrackError / crossTrackErrorRate, 0, 30, -limit, limit), -limit, limit); + float timeFactor = constrainf(navCrossTrackError / 100.0f, 10.0f, 30.0f); + rateFactor = constrainf(scaleRangef(navCrossTrackError / crossTrackErrorRate, 0.0f, timeFactor, -limit, limit), -limit, limit); } /* Determine final adjusted virtualTargetBearing */ From 069a61cea5e7e8fa2137349bdc8df120dbfda219 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Thu, 8 Aug 2024 10:16:35 +0200 Subject: [PATCH 174/212] add h7 svd file --- cmake/stm32h7.cmake | 1 + dev/svd/STM32H743.svd | 105015 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 105016 insertions(+) create mode 100644 dev/svd/STM32H743.svd diff --git a/cmake/stm32h7.cmake b/cmake/stm32h7.cmake index 08e7686b8f4..81a8b2d889d 100644 --- a/cmake/stm32h7.cmake +++ b/cmake/stm32h7.cmake @@ -216,6 +216,7 @@ macro(define_target_stm32h7 subfamily size) COMPILE_DEFINITIONS ${definitions} LINKER_SCRIPT stm32_flash_h7${subfamily}x${size} ${${func_ARGV}} + SVD STM32H7${subfamily} ) endfunction() endmacro() diff --git a/dev/svd/STM32H743.svd b/dev/svd/STM32H743.svd new file mode 100644 index 00000000000..768431e55a6 --- /dev/null +++ b/dev/svd/STM32H743.svd @@ -0,0 +1,105015 @@ + + + STM32H743 + 1.3 + STM32H743 + + CM7 + r0p1 + little + true + true + 4 + false + + + + 8 + + 32 + + 0x20 + 0x0 + 0xFFFFFFFF + + + COMP1 + COMP1 + COMP1 + 0x58003800 + + 0x0 + 0x400 + registers + + + COMP + COMP1 and COMP2 + 137 + + + + SR + SR + Comparator status register + 0x0 + 0x20 + read-only + 0x00000000 + + + C1VAL + COMP channel 1 output status + bit + 0 + 1 + + + C2VAL + COMP channel 2 output status + bit + 1 + 1 + + + C1IF + COMP channel 1 Interrupt + Flag + 16 + 1 + + + C2IF + COMP channel 2 Interrupt + Flag + 17 + 1 + + + + + ICFR + ICFR + Comparator interrupt clear flag + register + 0x4 + 0x20 + write-only + 0x00000000 + + + CC1IF + Clear COMP channel 1 Interrupt + Flag + 16 + 1 + + + CC2IF + Clear COMP channel 2 Interrupt + Flag + 17 + 1 + + + + + OR + OR + Comparator option register + 0x8 + 0x20 + read-write + 0x00000000 + + + AFOP + Selection of source for alternate + function of output ports + 0 + 11 + + + OR + Option Register + 11 + 21 + + + + + CFGR1 + CFGR1 + Comparator configuration register + 1 + 0xC + 0x20 + read-write + 0x00000000 + + + EN + COMP channel 1 enable bit + 0 + 1 + + + BRGEN + Scaler bridge enable + 1 + 1 + + + SCALEN + Voltage scaler enable bit + 2 + 1 + + + POLARITY + COMP channel 1 polarity selection + bit + 3 + 1 + + + ITEN + COMP channel 1 interrupt + enable + 6 + 1 + + + HYST + COMP channel 1 hysteresis selection + bits + 8 + 2 + + + PWRMODE + Power Mode of the COMP channel + 1 + 12 + 2 + + + INMSEL + COMP channel 1 inverting input selection + field + 16 + 3 + + + INPSEL + COMP channel 1 non-inverting input + selection bit + 20 + 1 + + + BLANKING + COMP channel 1 blanking source selection + bits + 24 + 4 + + + LOCK + Lock bit + 31 + 1 + + + + + CFGR2 + CFGR2 + Comparator configuration register + 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + EN + COMP channel 1 enable bit + 0 + 1 + + + BRGEN + Scaler bridge enable + 1 + 1 + + + SCALEN + Voltage scaler enable bit + 2 + 1 + + + POLARITY + COMP channel 1 polarity selection + bit + 3 + 1 + + + WINMODE + Window comparator mode selection + bit + 4 + 1 + + + ITEN + COMP channel 1 interrupt + enable + 6 + 1 + + + HYST + COMP channel 1 hysteresis selection + bits + 8 + 2 + + + PWRMODE + Power Mode of the COMP channel + 1 + 12 + 2 + + + INMSEL + COMP channel 1 inverting input selection + field + 16 + 3 + + + INPSEL + COMP channel 1 non-inverting input + selection bit + 20 + 1 + + + BLANKING + COMP channel 1 blanking source selection + bits + 24 + 4 + + + LOCK + Lock bit + 31 + 1 + + + + + + + CRS + CRS + CRS + 0x40008400 + + 0x0 + 0x400 + registers + + + CRS + Clock Recovery System globa + 144 + + + + CR + CR + CRS control register + 0x0 + 0x20 + 0x00002000 + + + SYNCOKIE + SYNC event OK interrupt + enable + 0 + 1 + read-write + + + SYNCWARNIE + SYNC warning interrupt + enable + 1 + 1 + read-write + + + ERRIE + Synchronization or trimming error + interrupt enable + 2 + 1 + read-write + + + ESYNCIE + Expected SYNC interrupt + enable + 3 + 1 + read-write + + + CEN + Frequency error counter enable This bit + enables the oscillator clock for the frequency error + counter. When this bit is set, the CRS_CFGR register + is write-protected and cannot be + modified. + 5 + 1 + read-write + + + AUTOTRIMEN + Automatic trimming enable This bit + enables the automatic hardware adjustment of TRIM + bits according to the measured frequency error + between two SYNC events. If this bit is set, the TRIM + bits are read-only. The TRIM value can be adjusted by + hardware by one or two steps at a time, depending on + the measured frequency error value. Refer to + Section7.3.4: Frequency error evaluation and + automatic trimming for more details. + 6 + 1 + read-write + + + SWSYNC + Generate software SYNC event This bit is + set by software in order to generate a software SYNC + event. It is automatically cleared by + hardware. + 7 + 1 + read-only + + + TRIM + HSI48 oscillator smooth trimming These + bits provide a user-programmable trimming value to + the HSI48 oscillator. They can be programmed to + adjust to variations in voltage and temperature that + influence the frequency of the HSI48. The default + value is 32, which corresponds to the middle of the + trimming interval. The trimming step is around 67 kHz + between two consecutive TRIM steps. A higher TRIM + value corresponds to a higher output frequency. When + the AUTOTRIMEN bit is set, this field is controlled + by hardware and is read-only. + 8 + 6 + read-write + + + + + CFGR + CFGR + This register can be written only when the + frequency error counter is disabled (CEN bit is cleared + in CRS_CR). When the counter is enabled, this register is + write-protected. + 0x4 + 0x20 + read-write + 0x2022BB7F + + + RELOAD + Counter reload value RELOAD is the value + to be loaded in the frequency error counter with each + SYNC event. Refer to Section7.3.3: Frequency error + measurement for more details about counter + behavior. + 0 + 16 + + + FELIM + Frequency error limit FELIM contains the + value to be used to evaluate the captured frequency + error value latched in the FECAP[15:0] bits of the + CRS_ISR register. Refer to Section7.3.4: Frequency + error evaluation and automatic trimming for more + details about FECAP evaluation. + 16 + 8 + + + SYNCDIV + SYNC divider These bits are set and + cleared by software to control the division factor of + the SYNC signal. + 24 + 3 + + + SYNCSRC + SYNC signal source selection These bits + are set and cleared by software to select the SYNC + signal source. Note: When using USB LPM (Link Power + Management) and the device is in Sleep mode, the + periodic USB SOF will not be generated by the host. + No SYNC signal will therefore be provided to the CRS + to calibrate the HSI48 on the run. To guarantee the + required clock precision after waking up from Sleep + mode, the LSE or reference clock on the GPIOs should + be used as SYNC signal. + 28 + 2 + + + SYNCPOL + SYNC polarity selection This bit is set + and cleared by software to select the input polarity + for the SYNC signal source. + 31 + 1 + + + + + ISR + ISR + CRS interrupt and status + register + 0x8 + 0x20 + read-only + 0x00000000 + + + SYNCOKF + SYNC event OK flag This flag is set by + hardware when the measured frequency error is smaller + than FELIM * 3. This means that either no adjustment + of the TRIM value is needed or that an adjustment by + one trimming step is enough to compensate the + frequency error. An interrupt is generated if the + SYNCOKIE bit is set in the CRS_CR register. It is + cleared by software by setting the SYNCOKC bit in the + CRS_ICR register. + 0 + 1 + + + SYNCWARNF + SYNC warning flag This flag is set by + hardware when the measured frequency error is greater + than or equal to FELIM * 3, but smaller than FELIM * + 128. This means that to compensate the frequency + error, the TRIM value must be adjusted by two steps + or more. An interrupt is generated if the SYNCWARNIE + bit is set in the CRS_CR register. It is cleared by + software by setting the SYNCWARNC bit in the CRS_ICR + register. + 1 + 1 + + + ERRF + Error flag This flag is set by hardware + in case of any synchronization or trimming error. It + is the logical OR of the TRIMOVF, SYNCMISS and + SYNCERR bits. An interrupt is generated if the ERRIE + bit is set in the CRS_CR register. It is cleared by + software in reaction to setting the ERRC bit in the + CRS_ICR register, which clears the TRIMOVF, SYNCMISS + and SYNCERR bits. + 2 + 1 + + + ESYNCF + Expected SYNC flag This flag is set by + hardware when the frequency error counter reached a + zero value. An interrupt is generated if the ESYNCIE + bit is set in the CRS_CR register. It is cleared by + software by setting the ESYNCC bit in the CRS_ICR + register. + 3 + 1 + + + SYNCERR + SYNC error This flag is set by hardware + when the SYNC pulse arrives before the ESYNC event + and the measured frequency error is greater than or + equal to FELIM * 128. This means that the frequency + error is too big (internal frequency too low) to be + compensated by adjusting the TRIM value, and that + some other action should be taken. An interrupt is + generated if the ERRIE bit is set in the CRS_CR + register. It is cleared by software by setting the + ERRC bit in the CRS_ICR register. + 8 + 1 + + + SYNCMISS + SYNC missed This flag is set by hardware + when the frequency error counter reached value FELIM + * 128 and no SYNC was detected, meaning either that a + SYNC pulse was missed or that the frequency error is + too big (internal frequency too high) to be + compensated by adjusting the TRIM value, and that + some other action should be taken. At this point, the + frequency error counter is stopped (waiting for a + next SYNC) and an interrupt is generated if the ERRIE + bit is set in the CRS_CR register. It is cleared by + software by setting the ERRC bit in the CRS_ICR + register. + 9 + 1 + + + TRIMOVF + Trimming overflow or underflow This flag + is set by hardware when the automatic trimming tries + to over- or under-flow the TRIM value. An interrupt + is generated if the ERRIE bit is set in the CRS_CR + register. It is cleared by software by setting the + ERRC bit in the CRS_ICR register. + 10 + 1 + + + FEDIR + Frequency error direction FEDIR is the + counting direction of the frequency error counter + latched in the time of the last SYNC event. It shows + whether the actual frequency is below or above the + target. + 15 + 1 + + + FECAP + Frequency error capture FECAP is the + frequency error counter value latched in the time of + the last SYNC event. Refer to Section7.3.4: Frequency + error evaluation and automatic trimming for more + details about FECAP usage. + 16 + 16 + + + + + ICR + ICR + CRS interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + SYNCOKC + SYNC event OK clear flag Writing 1 to + this bit clears the SYNCOKF flag in the CRS_ISR + register. + 0 + 1 + + + SYNCWARNC + SYNC warning clear flag Writing 1 to + this bit clears the SYNCWARNF flag in the CRS_ISR + register. + 1 + 1 + + + ERRC + Error clear flag Writing 1 to this bit + clears TRIMOVF, SYNCMISS and SYNCERR bits and + consequently also the ERRF flag in the CRS_ISR + register. + 2 + 1 + + + ESYNCC + Expected SYNC clear flag Writing 1 to + this bit clears the ESYNCF flag in the CRS_ISR + register. + 3 + 1 + + + + + + + DAC + DAC + DAC + 0x40007400 + + 0x0 + 0x400 + registers + + + + CR + CR + DAC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + EN1 + DAC channel1 enable This bit is set and + cleared by software to enable/disable DAC + channel1. + 0 + 1 + + + TEN1 + DAC channel1 trigger + enable + 1 + 1 + + + TSEL1 + DAC channel1 trigger selection These + bits select the external event used to trigger DAC + channel1. Note: Only used if bit TEN1 = 1 (DAC + channel1 trigger enabled). + 2 + 3 + + + WAVE1 + DAC channel1 noise/triangle wave + generation enable These bits are set and cleared by + software. Note: Only used if bit TEN1 = 1 (DAC + channel1 trigger enabled). + 6 + 2 + + + MAMP1 + DAC channel1 mask/amplitude selector + These bits are written by software to select mask in + wave generation mode or amplitude in triangle + generation mode. = 1011: Unmask bits[11:0] of LFSR/ + triangle amplitude equal to 4095 + 8 + 4 + + + DMAEN1 + DAC channel1 DMA enable This bit is set + and cleared by software. + 12 + 1 + + + DMAUDRIE1 + DAC channel1 DMA Underrun Interrupt + enable This bit is set and cleared by + software. + 13 + 1 + + + CEN1 + DAC Channel 1 calibration enable This + bit is set and cleared by software to enable/disable + DAC channel 1 calibration, it can be written only if + bit EN1=0 into DAC_CR (the calibration mode can be + entered/exit only when the DAC channel is disabled) + Otherwise, the write operation is + ignored. + 14 + 1 + + + EN2 + DAC channel2 enable This bit is set and + cleared by software to enable/disable DAC + channel2. + 16 + 1 + + + TEN2 + DAC channel2 trigger + enable + 17 + 1 + + + TSEL2 + DAC channel2 trigger selection These + bits select the external event used to trigger DAC + channel2 Note: Only used if bit TEN2 = 1 (DAC + channel2 trigger enabled). + 18 + 3 + + + WAVE2 + DAC channel2 noise/triangle wave + generation enable These bits are set/reset by + software. 1x: Triangle wave generation enabled Note: + Only used if bit TEN2 = 1 (DAC channel2 trigger + enabled) + 22 + 2 + + + MAMP2 + DAC channel2 mask/amplitude selector + These bits are written by software to select mask in + wave generation mode or amplitude in triangle + generation mode. = 1011: Unmask bits[11:0] of LFSR/ + triangle amplitude equal to 4095 + 24 + 4 + + + DMAEN2 + DAC channel2 DMA enable This bit is set + and cleared by software. + 28 + 1 + + + DMAUDRIE2 + DAC channel2 DMA underrun interrupt + enable This bit is set and cleared by + software. + 29 + 1 + + + CEN2 + DAC Channel 2 calibration enable This + bit is set and cleared by software to enable/disable + DAC channel 2 calibration, it can be written only if + bit EN2=0 into DAC_CR (the calibration mode can be + entered/exit only when the DAC channel is disabled) + Otherwise, the write operation is + ignored. + 30 + 1 + + + + + SWTRGR + SWTRGR + DAC software trigger register + 0x4 + 0x20 + write-only + 0x00000000 + + + SWTRIG1 + DAC channel1 software trigger This bit + is set by software to trigger the DAC in software + trigger mode. Note: This bit is cleared by hardware + (one APB1 clock cycle later) once the DAC_DHR1 + register value has been loaded into the DAC_DOR1 + register. + 0 + 1 + + + SWTRIG2 + DAC channel2 software trigger This bit + is set by software to trigger the DAC in software + trigger mode. Note: This bit is cleared by hardware + (one APB1 clock cycle later) once the DAC_DHR2 + register value has been loaded into the DAC_DOR2 + register. + 1 + 1 + + + + + DHR12R1 + DHR12R1 + DAC channel1 12-bit right-aligned data + holding register + 0x8 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel1. + 0 + 12 + + + + + DHR12L1 + DHR12L1 + DAC channel1 12-bit left aligned data + holding register + 0xC + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel1. + 4 + 12 + + + + + DHR8R1 + DHR8R1 + DAC channel1 8-bit right aligned data + holding register + 0x10 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned data + These bits are written by software which specifies + 8-bit data for DAC channel1. + 0 + 8 + + + + + DHR12R2 + DHR12R2 + DAC channel2 12-bit right aligned data + holding register + 0x14 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit right-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel2. + 0 + 12 + + + + + DHR12L2 + DHR12L2 + DAC channel2 12-bit left aligned data + holding register + 0x18 + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 12-bit left-aligned data + These bits are written by software which specify + 12-bit data for DAC channel2. + 4 + 12 + + + + + DHR8R2 + DHR8R2 + DAC channel2 8-bit right-aligned data + holding register + 0x1C + 0x20 + read-write + 0x00000000 + + + DACC2DHR + DAC channel2 8-bit right-aligned data + These bits are written by software which specifies + 8-bit data for DAC channel2. + 0 + 8 + + + + + DHR12RD + DHR12RD + Dual DAC 12-bit right-aligned data holding + register + 0x20 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit right-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel1. + 0 + 12 + + + DACC2DHR + DAC channel2 12-bit right-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel2. + 16 + 12 + + + + + DHR12LD + DHR12LD + DUAL DAC 12-bit left aligned data holding + register + 0x24 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 12-bit left-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel1. + 4 + 12 + + + DACC2DHR + DAC channel2 12-bit left-aligned data + These bits are written by software which specifies + 12-bit data for DAC channel2. + 20 + 12 + + + + + DHR8RD + DHR8RD + DUAL DAC 8-bit right aligned data holding + register + 0x28 + 0x20 + read-write + 0x00000000 + + + DACC1DHR + DAC channel1 8-bit right-aligned data + These bits are written by software which specifies + 8-bit data for DAC channel1. + 0 + 8 + + + DACC2DHR + DAC channel2 8-bit right-aligned data + These bits are written by software which specifies + 8-bit data for DAC channel2. + 8 + 8 + + + + + DOR1 + DOR1 + DAC channel1 data output + register + 0x2C + 0x20 + read-only + 0x00000000 + + + DACC1DOR + DAC channel1 data output These bits are + read-only, they contain data output for DAC + channel1. + 0 + 12 + + + + + DOR2 + DOR2 + DAC channel2 data output + register + 0x30 + 0x20 + read-only + 0x00000000 + + + DACC2DOR + DAC channel2 data output These bits are + read-only, they contain data output for DAC + channel2. + 0 + 12 + + + + + SR + SR + DAC status register + 0x34 + 0x20 + 0x00000000 + + + DMAUDR1 + DAC channel1 DMA underrun flag This bit + is set by hardware and cleared by software (by + writing it to 1). + 13 + 1 + read-write + + + CAL_FLAG1 + DAC Channel 1 calibration offset status + This bit is set and cleared by hardware + 14 + 1 + read-only + + + BWST1 + DAC Channel 1 busy writing sample time + flag This bit is systematically set just after Sample + & Hold mode enable and is set each time the + software writes the register DAC_SHSR1, It is cleared + by hardware when the write operation of DAC_SHSR1 is + complete. (It takes about 3LSI periods of + synchronization). + 15 + 1 + read-only + + + DMAUDR2 + DAC channel2 DMA underrun flag This bit + is set by hardware and cleared by software (by + writing it to 1). + 29 + 1 + read-write + + + CAL_FLAG2 + DAC Channel 2 calibration offset status + This bit is set and cleared by hardware + 30 + 1 + read-only + + + BWST2 + DAC Channel 2 busy writing sample time + flag This bit is systematically set just after Sample + & Hold mode enable and is set each time the + software writes the register DAC_SHSR2, It is cleared + by hardware when the write operation of DAC_SHSR2 is + complete. (It takes about 3 LSI periods of + synchronization). + 31 + 1 + read-only + + + + + CCR + CCR + DAC calibration control + register + 0x38 + 0x20 + read-write + 0x00000000 + + + OTRIM1 + DAC Channel 1 offset trimming + value + 0 + 5 + + + OTRIM2 + DAC Channel 2 offset trimming + value + 16 + 5 + + + + + MCR + MCR + DAC mode control register + 0x3C + 0x20 + read-write + 0x00000000 + + + MODE1 + DAC Channel 1 mode These bits can be + written only when the DAC is disabled and not in the + calibration mode (when bit EN1=0 and bit CEN1 =0 in + the DAC_CR register). If EN1=1 or CEN1 =1 the write + operation is ignored. They can be set and cleared by + software to select the DAC Channel 1 mode: DAC + Channel 1 in normal Mode DAC Channel 1 in sample + &amp; hold mode + 0 + 3 + + + MODE2 + DAC Channel 2 mode These bits can be + written only when the DAC is disabled and not in the + calibration mode (when bit EN2=0 and bit CEN2 =0 in + the DAC_CR register). If EN2=1 or CEN2 =1 the write + operation is ignored. They can be set and cleared by + software to select the DAC Channel 2 mode: DAC + Channel 2 in normal Mode DAC Channel 2 in sample + &amp; hold mode + 16 + 3 + + + + + SHSR1 + SHSR1 + DAC Sample and Hold sample time register + 1 + 0x40 + 0x20 + read-write + 0x00000000 + + + TSAMPLE1 + DAC Channel 1 sample Time (only valid in + sample &amp; hold mode) These bits can be written + when the DAC channel1 is disabled or also during + normal operation. in the latter case, the write can + be done only when BWSTx of DAC_SR register is low, If + BWSTx=1, the write operation is + ignored. + 0 + 10 + + + + + SHSR2 + SHSR2 + DAC Sample and Hold sample time register + 2 + 0x44 + 0x20 + read-write + 0x00000000 + + + TSAMPLE2 + DAC Channel 2 sample Time (only valid in + sample &amp; hold mode) These bits can be written + when the DAC channel2 is disabled or also during + normal operation. in the latter case, the write can + be done only when BWSTx of DAC_SR register is low, if + BWSTx=1, the write operation is + ignored. + 0 + 10 + + + + + SHHR + SHHR + DAC Sample and Hold hold time + register + 0x48 + 0x20 + read-write + 0x00010001 + + + THOLD1 + DAC Channel 1 hold Time (only valid in + sample &amp; hold mode) Hold time= (THOLD[9:0]) x + T LSI + 0 + 10 + + + THOLD2 + DAC Channel 2 hold time (only valid in + sample &amp; hold mode). Hold time= (THOLD[9:0]) + x T LSI + 16 + 10 + + + + + SHRR + SHRR + DAC Sample and Hold refresh time + register + 0x4C + 0x20 + read-write + 0x00010001 + + + TREFRESH1 + DAC Channel 1 refresh Time (only valid + in sample &amp; hold mode) Refresh time= + (TREFRESH[7:0]) x T LSI + 0 + 8 + + + TREFRESH2 + DAC Channel 2 refresh Time (only valid + in sample &amp; hold mode) Refresh time= + (TREFRESH[7:0]) x T LSI + 16 + 8 + + + + + + + BDMA + BDMA + BDMA + 0x58025400 + + 0x0 + 0x400 + registers + + + BDMA_CH1 + BDMA channel 1 interrupt + 129 + + + BDMA_CH2 + BDMA channel 2 interrupt + 130 + + + BDMA_CH3 + BDMA channel 3 interrupt + 131 + + + BDMA_CH4 + BDMA channel 4 interrupt + 132 + + + BDMA_CH5 + BDMA channel 5 interrupt + 133 + + + BDMA_CH6 + BDMA channel 6 interrupt + 134 + + + BDMA_CH7 + BDMA channel 7 interrupt + 135 + + + BDMA_CH8 + BDMA channel 8 interrupt + 136 + + + + ISR + ISR + DMA interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + GIF1 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 0 + 1 + + + TCIF1 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 1 + 1 + + + HTIF1 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 2 + 1 + + + TEIF1 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 3 + 1 + + + GIF2 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 4 + 1 + + + TCIF2 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 5 + 1 + + + HTIF2 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 6 + 1 + + + TEIF2 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 7 + 1 + + + GIF3 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 8 + 1 + + + TCIF3 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 9 + 1 + + + HTIF3 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 10 + 1 + + + TEIF3 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 11 + 1 + + + GIF4 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 12 + 1 + + + TCIF4 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 13 + 1 + + + HTIF4 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 14 + 1 + + + TEIF4 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 15 + 1 + + + GIF5 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 16 + 1 + + + TCIF5 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 17 + 1 + + + HTIF5 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 18 + 1 + + + TEIF5 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 19 + 1 + + + GIF6 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 20 + 1 + + + TCIF6 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 21 + 1 + + + HTIF6 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 22 + 1 + + + TEIF6 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 23 + 1 + + + GIF7 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 24 + 1 + + + TCIF7 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 25 + 1 + + + HTIF7 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 26 + 1 + + + TEIF7 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 27 + 1 + + + GIF8 + Channel x global interrupt flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 28 + 1 + + + TCIF8 + Channel x transfer complete flag (x = + 1..8) This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 29 + 1 + + + HTIF8 + Channel x half transfer flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 30 + 1 + + + TEIF8 + Channel x transfer error flag (x = 1..8) + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCR register. + 31 + 1 + + + + + IFCR + IFCR + DMA interrupt flag clear + register + 0x4 + 0x20 + write-only + 0x00000000 + + + CGIF1 + Channel x global interrupt clear This + bit is set and cleared by software. + 0 + 1 + + + CTCIF1 + Channel x transfer complete clear This + bit is set and cleared by software. + 1 + 1 + + + CHTIF1 + Channel x half transfer clear This bit + is set and cleared by software. + 2 + 1 + + + CTEIF1 + Channel x transfer error clear This bit + is set and cleared by software. + 3 + 1 + + + CGIF2 + Channel x global interrupt clear This + bit is set and cleared by software. + 4 + 1 + + + CTCIF2 + Channel x transfer complete clear This + bit is set and cleared by software. + 5 + 1 + + + CHTIF2 + Channel x half transfer clear This bit + is set and cleared by software. + 6 + 1 + + + CTEIF2 + Channel x transfer error clear This bit + is set and cleared by software. + 7 + 1 + + + CGIF3 + Channel x global interrupt clear This + bit is set and cleared by software. + 8 + 1 + + + CTCIF3 + Channel x transfer complete clear This + bit is set and cleared by software. + 9 + 1 + + + CHTIF3 + Channel x half transfer clear This bit + is set and cleared by software. + 10 + 1 + + + CTEIF3 + Channel x transfer error clear This bit + is set and cleared by software. + 11 + 1 + + + CGIF4 + Channel x global interrupt clear This + bit is set and cleared by software. + 12 + 1 + + + CTCIF4 + Channel x transfer complete clear This + bit is set and cleared by software. + 13 + 1 + + + CHTIF4 + Channel x half transfer clear This bit + is set and cleared by software. + 14 + 1 + + + CTEIF4 + Channel x transfer error clear This bit + is set and cleared by software. + 15 + 1 + + + CGIF5 + Channel x global interrupt clear This + bit is set and cleared by software. + 16 + 1 + + + CTCIF5 + Channel x transfer complete clear This + bit is set and cleared by software. + 17 + 1 + + + CHTIF5 + Channel x half transfer clear This bit + is set and cleared by software. + 18 + 1 + + + CTEIF5 + Channel x transfer error clear This bit + is set and cleared by software. + 19 + 1 + + + CGIF6 + Channel x global interrupt clear This + bit is set and cleared by software. + 20 + 1 + + + CTCIF6 + Channel x transfer complete clear This + bit is set and cleared by software. + 21 + 1 + + + CHTIF6 + Channel x half transfer clear This bit + is set and cleared by software. + 22 + 1 + + + CTEIF6 + Channel x transfer error clear This bit + is set and cleared by software. + 23 + 1 + + + CGIF7 + Channel x global interrupt clear This + bit is set and cleared by software. + 24 + 1 + + + CTCIF7 + Channel x transfer complete clear This + bit is set and cleared by software. + 25 + 1 + + + CHTIF7 + Channel x half transfer clear This bit + is set and cleared by software. + 26 + 1 + + + CTEIF7 + Channel x transfer error clear This bit + is set and cleared by software. + 27 + 1 + + + CGIF8 + Channel x global interrupt clear This + bit is set and cleared by software. + 28 + 1 + + + CTCIF8 + Channel x transfer complete clear This + bit is set and cleared by software. + 29 + 1 + + + CHTIF8 + Channel x half transfer clear This bit + is set and cleared by software. + 30 + 1 + + + CTEIF8 + Channel x transfer error clear This bit + is set and cleared by software. + 31 + 1 + + + + + CCR1 + CCR1 + DMA channel x configuration + register + 0x8 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR1 + CNDTR1 + DMA channel x number of data + register + 0xC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR1 + CPAR1 + This register must not be written when the + channel is enabled. + 0x10 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR1 + CMAR1 + This register must not be written when the + channel is enabled. + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR2 + CCR2 + DMA channel x configuration + register + 0x1C + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR2 + CNDTR2 + DMA channel x number of data + register + 0x20 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR2 + CPAR2 + This register must not be written when the + channel is enabled. + 0x24 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR2 + CMAR2 + This register must not be written when the + channel is enabled. + 0x28 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR3 + CCR3 + DMA channel x configuration + register + 0x30 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR3 + CNDTR3 + DMA channel x number of data + register + 0x34 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR3 + CPAR3 + This register must not be written when the + channel is enabled. + 0x38 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR3 + CMAR3 + This register must not be written when the + channel is enabled. + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR4 + CCR4 + DMA channel x configuration + register + 0x44 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR4 + CNDTR4 + DMA channel x number of data + register + 0x48 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR4 + CPAR4 + This register must not be written when the + channel is enabled. + 0x4C + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR4 + CMAR4 + This register must not be written when the + channel is enabled. + 0x50 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR5 + CCR5 + DMA channel x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR5 + CNDTR5 + DMA channel x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR5 + CPAR5 + This register must not be written when the + channel is enabled. + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR5 + CMAR5 + This register must not be written when the + channel is enabled. + 0x64 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR6 + CCR6 + DMA channel x configuration + register + 0x6C + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR6 + CNDTR6 + DMA channel x number of data + register + 0x70 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR6 + CPAR6 + This register must not be written when the + channel is enabled. + 0x74 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR6 + CMAR6 + This register must not be written when the + channel is enabled. + 0x78 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR7 + CCR7 + DMA channel x configuration + register + 0x80 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR7 + CNDTR7 + DMA channel x number of data + register + 0x84 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR7 + CPAR7 + This register must not be written when the + channel is enabled. + 0x88 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR7 + CMAR7 + This register must not be written when the + channel is enabled. + 0x8C + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CCR8 + CCR8 + DMA channel x configuration + register + 0x94 + 0x20 + read-write + 0x00000000 + + + EN + Channel enable This bit is set and + cleared by software. + 0 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 1 + 1 + + + HTIE + Half transfer interrupt enable This bit + is set and cleared by software. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 3 + 1 + + + DIR + Data transfer direction This bit is set + and cleared by software. + 4 + 1 + + + CIRC + Circular mode This bit is set and + cleared by software. + 5 + 1 + + + PINC + Peripheral increment mode This bit is + set and cleared by software. + 6 + 1 + + + MINC + Memory increment mode This bit is set + and cleared by software. + 7 + 1 + + + PSIZE + Peripheral size These bits are set and + cleared by software. + 8 + 2 + + + MSIZE + Memory size These bits are set and + cleared by software. + 10 + 2 + + + PL + Channel priority level These bits are + set and cleared by software. + 12 + 2 + + + MEM2MEM + Memory to memory mode This bit is set + and cleared by software. + 14 + 1 + + + + + CNDTR8 + CNDTR8 + DMA channel x number of data + register + 0x98 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data to transfer Number of + data to be transferred (0 up to 65535). This register + can only be written when the channel is disabled. + Once the channel is enabled, this register is + read-only, indicating the remaining bytes to be + transmitted. This register decrements after each DMA + transfer. Once the transfer is completed, this + register can either stay at zero or be reloaded + automatically by the value previously programmed if + the channel is configured in auto-reload mode. If + this register is zero, no transaction can be served + whether the channel is enabled or not. + 0 + 16 + + + + + CPAR8 + CPAR8 + This register must not be written when the + channel is enabled. + 0x9C + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address Base address of the + peripheral data register from/to which the data will + be read/written. When PSIZE is 01 (16-bit), the PA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When PSIZE is 10 (32-bit), PA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + CMAR8 + CMAR8 + This register must not be written when the + channel is enabled. + 0xA0 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Base address of the + memory area from/to which the data will be + read/written. When MSIZE is 01 (16-bit), the MA[0] + bit is ignored. Access is automatically aligned to a + half-word address. When MSIZE is 10 (32-bit), MA[1:0] + are ignored. Access is automatically aligned to a + word address. + 0 + 32 + + + + + + + DMA2D + DMA2D + DMA2D + 0x52001000 + + 0x0 + 0x400 + registers + + + DMA2D + DMA2D global interrupt + 90 + + + + CR + CR + DMA2D control register + 0x0 + 0x20 + read-write + 0x00000000 + + + START + Start This bit can be used to launch the + DMA2D according to the parameters loaded in the + various configuration registers + 0 + 1 + + + SUSP + Suspend This bit can be used to suspend + the current transfer. This bit is set and reset by + software. It is automatically reset by hardware when + the START bit is reset. + 1 + 1 + + + ABORT + Abort This bit can be used to abort the + current transfer. This bit is set by software and is + automatically reset by hardware when the START bit is + reset. + 2 + 1 + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 8 + 1 + + + TCIE + Transfer complete interrupt enable This + bit is set and cleared by software. + 9 + 1 + + + TWIE + Transfer watermark interrupt enable This + bit is set and cleared by software. + 10 + 1 + + + CAEIE + CLUT access error interrupt enable This + bit is set and cleared by software. + 11 + 1 + + + CTCIE + CLUT transfer complete interrupt enable + This bit is set and cleared by + software. + 12 + 1 + + + CEIE + Configuration Error Interrupt Enable + This bit is set and cleared by + software. + 13 + 1 + + + MODE + DMA2D mode This bit is set and cleared + by software. It cannot be modified while a transfer + is ongoing. + 16 + 2 + + + + + ISR + ISR + DMA2D Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + TEIF + Transfer error interrupt flag This bit + is set when an error occurs during a DMA transfer + (data transfer or automatic CLUT + loading). + 0 + 1 + + + TCIF + Transfer complete interrupt flag This + bit is set when a DMA2D transfer operation is + complete (data transfer only). + 1 + 1 + + + TWIF + Transfer watermark interrupt flag This + bit is set when the last pixel of the watermarked + line has been transferred. + 2 + 1 + + + CAEIF + CLUT access error interrupt flag This + bit is set when the CPU accesses the CLUT while the + CLUT is being automatically copied from a system + memory to the internal DMA2D. + 3 + 1 + + + CTCIF + CLUT transfer complete interrupt flag + This bit is set when the CLUT copy from a system + memory area to the internal DMA2D memory is + complete. + 4 + 1 + + + CEIF + Configuration error interrupt flag This + bit is set when the START bit of DMA2D_CR, + DMA2DFGPFCCR or DMA2D_BGPFCCR is set and a wrong + configuration has been programmed. + 5 + 1 + + + + + IFCR + IFCR + DMA2D interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTEIF + Clear Transfer error interrupt flag + Programming this bit to 1 clears the TEIF flag in the + DMA2D_ISR register + 0 + 1 + + + CTCIF + Clear transfer complete interrupt flag + Programming this bit to 1 clears the TCIF flag in the + DMA2D_ISR register + 1 + 1 + + + CTWIF + Clear transfer watermark interrupt flag + Programming this bit to 1 clears the TWIF flag in the + DMA2D_ISR register + 2 + 1 + + + CAECIF + Clear CLUT access error interrupt flag + Programming this bit to 1 clears the CAEIF flag in + the DMA2D_ISR register + 3 + 1 + + + CCTCIF + Clear CLUT transfer complete interrupt + flag Programming this bit to 1 clears the CTCIF flag + in the DMA2D_ISR register + 4 + 1 + + + CCEIF + Clear configuration error interrupt flag + Programming this bit to 1 clears the CEIF flag in the + DMA2D_ISR register + 5 + 1 + + + + + FGMAR + FGMAR + DMA2D foreground memory address + register + 0xC + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the foreground image. This register can only be + written when data transfers are disabled. Once the + data transfer has started, this register is + read-only. The address alignment must match the image + format selected e.g. a 32-bit per pixel format must + be 32-bit aligned, a 16-bit per pixel format must be + 16-bit aligned and a 4-bit per pixel format must be + 8-bit aligned. + 0 + 32 + + + + + FGOR + FGOR + DMA2D foreground offset + register + 0x10 + 0x20 + read-write + 0x00000000 + + + LO + Line offset Line offset used for the + foreground expressed in pixel. This value is used to + generate the address. It is added at the end of each + line to determine the starting address of the next + line. These bits can only be written when data + transfers are disabled. Once a data transfer has + started, they become read-only. If the image format + is 4-bit per pixel, the line offset must be + even. + 0 + 14 + + + + + BGMAR + BGMAR + DMA2D background memory address + register + 0x14 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the background image. This register can only be + written when data transfers are disabled. Once a data + transfer has started, this register is read-only. The + address alignment must match the image format + selected e.g. a 32-bit per pixel format must be + 32-bit aligned, a 16-bit per pixel format must be + 16-bit aligned and a 4-bit per pixel format must be + 8-bit aligned. + 0 + 32 + + + + + BGOR + BGOR + DMA2D background offset + register + 0x18 + 0x20 + read-write + 0x00000000 + + + LO + Line offset Line offset used for the + background image (expressed in pixel). This value is + used for the address generation. It is added at the + end of each line to determine the starting address of + the next line. These bits can only be written when + data transfers are disabled. Once data transfer has + started, they become read-only. If the image format + is 4-bit per pixel, the line offset must be + even. + 0 + 14 + + + + + FGPFCCR + FGPFCCR + DMA2D foreground PFC control + register + 0x1C + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits defines the color + format of the foreground image. They can only be + written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 4 + + + CCM + CLUT color mode This bit defines the + color format of the CLUT. It can only be written when + the transfer is disabled. Once the CLUT transfer has + started, this bit is read-only. + 4 + 1 + + + START + Start This bit can be set to start the + automatic loading of the CLUT. It is automatically + reset: ** at the end of the transfer ** when the + transfer is aborted by the user application by + setting the ABORT bit in DMA2D_CR ** when a transfer + error occurs ** when the transfer has not started due + to a configuration error or another transfer + operation already ongoing (data transfer or automatic + background CLUT transfer). + 5 + 1 + + + CS + CLUT size These bits define the size of + the CLUT used for the foreground image. Once the CLUT + transfer has started, this field is read-only. The + number of CLUT entries is equal to CS[7:0] + + 1. + 8 + 8 + + + AM + Alpha mode These bits select the alpha + channel value to be used for the foreground image. + They can only be written data the transfer are + disabled. Once the transfer has started, they become + read-only. other configurations are + meaningless + 16 + 2 + + + CSS + Chroma Sub-Sampling These bits define + the chroma sub-sampling mode for YCbCr color mode. + Once the transfer has started, these bits are + read-only. others: meaningless + 18 + 2 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + ALPHA + Alpha value These bits define a fixed + alpha channel value which can replace the original + alpha value or be multiplied by the original alpha + value according to the alpha mode selected through + the AM[1:0] bits. These bits can only be written when + data transfers are disabled. Once a transfer has + started, they become read-only. + 24 + 8 + + + + + FGCOLR + FGCOLR + DMA2D foreground color + register + 0x20 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits defines the blue + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, They are + read-only. + 0 + 8 + + + GREEN + Green Value These bits defines the green + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, They are + read-only. + 8 + 8 + + + RED + Red Value These bits defines the red + value for the A4 or A8 mode of the foreground image. + They can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 16 + 8 + + + + + BGPFCCR + BGPFCCR + DMA2D background PFC control + register + 0x24 + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits define the color + format of the foreground image. These bits can only + be written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 4 + + + CCM + CLUT Color mode These bits define the + color format of the CLUT. This register can only be + written when the transfer is disabled. Once the CLUT + transfer has started, this bit is + read-only. + 4 + 1 + + + START + Start This bit is set to start the + automatic loading of the CLUT. This bit is + automatically reset: ** at the end of the transfer ** + when the transfer is aborted by the user application + by setting the ABORT bit in the DMA2D_CR ** when a + transfer error occurs ** when the transfer has not + started due to a configuration error or another + transfer operation already on going (data transfer or + automatic BackGround CLUT transfer). + 5 + 1 + + + CS + CLUT size These bits define the size of + the CLUT used for the BG. Once the CLUT transfer has + started, this field is read-only. The number of CLUT + entries is equal to CS[7:0] + 1. + 8 + 8 + + + AM + Alpha mode These bits define which alpha + channel value to be used for the background image. + These bits can only be written when data transfers + are disabled. Once the transfer has started, they are + read-only. others: meaningless + 16 + 2 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + ALPHA + Alpha value These bits define a fixed + alpha channel value which can replace the original + alpha value or be multiplied with the original alpha + value according to the alpha mode selected with bits + AM[1: 0]. These bits can only be written when data + transfers are disabled. Once the transfer has + started, they are read-only. + 24 + 8 + + + + + BGCOLR + BGCOLR + DMA2D background color + register + 0x28 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits define the blue + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 0 + 8 + + + GREEN + Green Value These bits define the green + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 8 + 8 + + + RED + Red Value These bits define the red + value for the A4 or A8 mode of the background. These + bits can only be written when data transfers are + disabled. Once the transfer has started, they are + read-only. + 16 + 8 + + + + + FGCMAR + FGCMAR + DMA2D foreground CLUT memory address + register + 0x2C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address Address of the data used + for the CLUT address dedicated to the foreground + image. This register can only be written when no + transfer is ongoing. Once the CLUT transfer has + started, this register is read-only. If the + foreground CLUT format is 32-bit, the address must be + 32-bit aligned. + 0 + 32 + + + + + BGCMAR + BGCMAR + DMA2D background CLUT memory address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + MA + Memory address Address of the data used + for the CLUT address dedicated to the background + image. This register can only be written when no + transfer is on going. Once the CLUT transfer has + started, this register is read-only. If the + background CLUT format is 32-bit, the address must be + 32-bit aligned. + 0 + 32 + + + + + OPFCCR + OPFCCR + DMA2D output PFC control + register + 0x34 + 0x20 + read-write + 0x00000000 + + + CM + Color mode These bits define the color + format of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are read-only. others: + meaningless + 0 + 3 + + + AI + Alpha Inverted This bit inverts the + alpha value. Once the transfer has started, this bit + is read-only. + 20 + 1 + + + RBS + Red Blue Swap This bit allows to swap + the R &amp; B to support BGR or ABGR color + formats. Once the transfer has started, this bit is + read-only. + 21 + 1 + + + + + OCOLR + OCOLR + DMA2D output color register + 0x38 + 0x20 + read-write + 0x00000000 + + + BLUE + Blue Value These bits define the blue + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 0 + 8 + + + GREEN + Green Value These bits define the green + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 8 + 8 + + + RED + Red Value These bits define the red + value of the output image. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 16 + 8 + + + ALPHA + Alpha Channel Value These bits define + the alpha channel of the output color. These bits can + only be written when data transfers are disabled. + Once the transfer has started, they are + read-only. + 24 + 8 + + + + + OMAR + OMAR + DMA2D output memory address + register + 0x3C + 0x20 + read-write + 0x00000000 + + + MA + Memory Address Address of the data used + for the output FIFO. These bits can only be written + when data transfers are disabled. Once the transfer + has started, they are read-only. The address + alignment must match the image format selected e.g. a + 32-bit per pixel format must be 32-bit aligned and a + 16-bit per pixel format must be 16-bit + aligned. + 0 + 32 + + + + + OOR + OOR + DMA2D output offset register + 0x40 + 0x20 + read-write + 0x00000000 + + + LO + Line Offset Line offset used for the + output (expressed in pixels). This value is used for + the address generation. It is added at the end of + each line to determine the starting address of the + next line. These bits can only be written when data + transfers are disabled. Once the transfer has + started, they are read-only. + 0 + 14 + + + + + NLR + NLR + DMA2D number of line register + 0x44 + 0x20 + read-write + 0x00000000 + + + NL + Number of lines Number of lines of the + area to be transferred. These bits can only be + written when data transfers are disabled. Once the + transfer has started, they are + read-only. + 0 + 16 + + + PL + Pixel per lines Number of pixels per + lines of the area to be transferred. These bits can + only be written when data transfers are disabled. + Once the transfer has started, they are read-only. If + any of the input image format is 4-bit per pixel, + pixel per lines must be even. + 16 + 14 + + + + + LWR + LWR + DMA2D line watermark register + 0x48 + 0x20 + read-write + 0x00000000 + + + LW + Line watermark These bits allow to + configure the line watermark for interrupt + generation. An interrupt is raised when the last + pixel of the watermarked line has been transferred. + These bits can only be written when data transfers + are disabled. Once the transfer has started, they are + read-only. + 0 + 16 + + + + + AMTCR + AMTCR + DMA2D AXI master timer configuration + register + 0x4C + 0x20 + read-write + 0x00000000 + + + EN + Enable Enables the dead time + functionality. + 0 + 1 + + + DT + Dead Time Dead time value in the AXI + clock cycle inserted between two consecutive accesses + on the AXI master port. These bits represent the + minimum guaranteed number of cycles between two + consecutive AXI accesses. + 8 + 8 + + + + + + + DMAMUX2 + DMAMUX + DMAMUX + 0x58025800 + + 0x0 + 0x400 + registers + + + DMAMUX2_OVR + DMAMUX2 overrun interrupt + 128 + + + + C0CR + C0CR + DMAMux - DMA request line multiplexer + channel x control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C1CR + C1CR + DMAMux - DMA request line multiplexer + channel x control register + 0x4 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C2CR + C2CR + DMAMux - DMA request line multiplexer + channel x control register + 0x8 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C3CR + C3CR + DMAMux - DMA request line multiplexer + channel x control register + 0xC + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C4CR + C4CR + DMAMux - DMA request line multiplexer + channel x control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C5CR + C5CR + DMAMux - DMA request line multiplexer + channel x control register + 0x14 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C6CR + C6CR + DMAMux - DMA request line multiplexer + channel x control register + 0x18 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C7CR + C7CR + DMAMux - DMA request line multiplexer + channel x control register + 0x1C + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + RG0CR + RG0CR + DMAMux - DMA request generator channel x + control register + 0x100 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG1CR + RG1CR + DMAMux - DMA request generator channel x + control register + 0x104 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG2CR + RG2CR + DMAMux - DMA request generator channel x + control register + 0x108 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG3CR + RG3CR + DMAMux - DMA request generator channel x + control register + 0x10C + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG4CR + RG4CR + DMAMux - DMA request generator channel x + control register + 0x110 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG5CR + RG5CR + DMAMux - DMA request generator channel x + control register + 0x114 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG6CR + RG6CR + DMAMux - DMA request generator channel x + control register + 0x118 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG7CR + RG7CR + DMAMux - DMA request generator channel x + control register + 0x11C + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RGSR + RGSR + DMAMux - DMA request generator status + register + 0x140 + 0x20 + read-only + 0x00000000 + + + OF + Trigger event overrun flag The flag is + set when a trigger event occurs on DMA request + generator channel x, while the DMA request generator + counter value is lower than GNBREQ. The flag is + cleared by writing 1 to the corresponding COFx bit in + DMAMUX_RGCFR register. + 0 + 8 + + + + + RGCFR + RGCFR + DMAMux - DMA request generator clear flag + register + 0x144 + 0x20 + write-only + 0x00000000 + + + COF + Clear trigger event overrun flag Upon + setting, this bit clears the corresponding overrun + flag OFx in the DMAMUX_RGCSR register. + 0 + 8 + + + + + CSR + CSR + DMAMUX request line multiplexer interrupt + channel status register + 0x80 + 0x20 + read-only + 0x00000000 + + + SOF + Synchronization overrun event + flag + 0 + 16 + + + + + CFR + CFR + DMAMUX request line multiplexer interrupt + clear flag register + 0x84 + 0x20 + write-only + 0x00000000 + + + CSOF + Clear synchronization overrun event + flag + 0 + 16 + + + + + + + FMC + FMC + FMC + 0x52004000 + + 0x0 + 0x400 + registers + + + FMC + FMC global interrupt + 48 + + + + BCR1 + BCR1 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories. + 0x0 + 0x20 + read-write + 0x000030DB + + + MBKEN + Memory bank enable bit This bit enables + the memory bank. After reset Bank1 is enabled, all + others are disabled. Accessing a disabled bank causes + an ERROR on AXI bus. + 0 + 1 + + + MUXEN + Address/data multiplexing enable bit + When this bit is set, the address and data values are + multiplexed on the data bus, valid only with NOR and + PSRAM memories: + 1 + 1 + + + MTYP + Memory type These bits define the type + of external memory attached to the corresponding + memory bank: + 2 + 2 + + + MWID + Memory data bus width Defines the + external memory device width, valid for all type of + memories. + 4 + 2 + + + FACCEN + Flash access enable This bit enables NOR + Flash memory access operations. + 6 + 1 + + + BURSTEN + Burst enable bit This bit + enables/disables synchronous accesses during read + operations. It is valid only for synchronous memories + operating in Burst mode: + 8 + 1 + + + WAITPOL + Wait signal polarity bit This bit + defines the polarity of the wait signal from memory + used for either in synchronous or asynchronous + mode: + 9 + 1 + + + WAITCFG + Wait timing configuration The NWAIT + signal indicates whether the data from the memory are + valid or if a wait state must be inserted when + accessing the memory in synchronous mode. This + configuration bit determines if NWAIT is asserted by + the memory one clock cycle before the wait state or + during the wait state: + 11 + 1 + + + WREN + Write enable bit This bit indicates + whether write operations are enabled/disabled in the + bank by the FMC: + 12 + 1 + + + WAITEN + Wait enable bit This bit + enables/disables wait-state insertion via the NWAIT + signal when accessing the memory in synchronous + mode. + 13 + 1 + + + EXTMOD + Extended mode enable. This bit enables + the FMC to program the write timings for asynchronous + accesses inside the FMC_BWTR register, thus resulting + in different timings for read and write operations. + Note: When the extended mode is disabled, the FMC can + operate in Mode1 or Mode2 as follows: ** Mode 1 is + the default mode when the SRAM/PSRAM memory type is + selected (MTYP =0x0 or 0x01) ** Mode 2 is the default + mode when the NOR memory type is selected (MTYP = + 0x10). + 14 + 1 + + + ASYNCWAIT + Wait signal during asynchronous + transfers This bit enables/disables the FMC to use + the wait signal even during an asynchronous + protocol. + 15 + 1 + + + CPSIZE + CRAM Page Size These are used for + Cellular RAM 1.5 which does not allow burst access to + cross the address boundaries between pages. When + these bits are configured, the FMC controller splits + automatically the burst access when the memory page + size is reached (refer to memory datasheet for page + size). Other configuration: reserved. + 16 + 3 + + + CBURSTRW + Write burst enable For PSRAM (CRAM) + operating in Burst mode, the bit enables synchronous + accesses during write operations. The enable bit for + synchronous read accesses is the BURSTEN bit in the + FMC_BCRx register. + 19 + 1 + + + CCLKEN + Continuous Clock Enable This bit enables + the FMC_CLK clock output to external memory devices. + Note: The CCLKEN bit of the FMC_BCR2..4 registers is + dont care. It is only enabled through the FMC_BCR1 + register. Bank 1 must be configured in synchronous + mode to generate the FMC_CLK continuous clock. If + CCLKEN bit is set, the FMC_CLK clock ratio is + specified by CLKDIV value in the FMC_BTR1 register. + CLKDIV in FMC_BWTR1 is dont care. If the synchronous + mode is used and CCLKEN bit is set, the synchronous + memories connected to other banks than Bank 1 are + clocked by the same clock (the CLKDIV value in the + FMC_BTR2..4 and FMC_BWTR2..4 registers for other + banks has no effect.) + 20 + 1 + + + WFDIS + Write FIFO Disable This bit disables the + Write FIFO used by the FMC controller. Note: The + WFDIS bit of the FMC_BCR2..4 registers is dont care. + It is only enabled through the FMC_BCR1 + register. + 21 + 1 + + + BMAP + FMC bank mapping These bits allows + different to remap SDRAM bank2 or swap the FMC + NOR/PSRAM and SDRAM banks.Refer to Table 10 for Note: + The BMAP bits of the FMC_BCR2..4 registers are dont + care. It is only enabled through the FMC_BCR1 + register. + 24 + 2 + + + FMCEN + FMC controller Enable This bit + enables/disables the FMC controller. Note: The FMCEN + bit of the FMC_BCR2..4 registers is dont care. It is + only enabled through the FMC_BCR1 + register. + 31 + 1 + + + + + BTR1 + BTR1 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories.If the EXTMOD bit is set in the + FMC_BCRx register, then this register is partitioned for + write and read access, that is, 2 registers are + available: one to configure read accesses (this register) + and one to configure write accesses (FMC_BWTRx + registers). + 0x4 + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration These bits + are written by software to define the duration of the + address setup phase (refer to Figure81 to Figure93), + used in SRAMs, ROMs and asynchronous NOR Flash: For + each access mode address setup phase duration, please + refer to the respective figure (refer to Figure81 to + Figure93). Note: In synchronous accesses, this value + is dont care. In Muxed mode or Mode D, the minimum + value for ADDSET is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in mode D or multiplexed accesses: For each + access mode address-hold phase duration, please refer + to the respective figure (Figure81 to Figure93). + Note: In synchronous accesses, this value is not + used, the address hold phase is always 1 memory clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous accesses: For each memory type and + access mode data-phase duration, please refer to the + respective figure (Figure81 to Figure93). Example: + Mode1, write access, DATAST=1: Data-phase duration= + DATAST+1 = 2 KCK_FMC clock cycles. Note: In + synchronous accesses, this value is dont + care. + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write-to-read or read-to write transaction. The + programmed bus turnaround delay is inserted between + an asynchronous read (in muxed or mode D) or write + transaction and any other asynchronous /synchronous + read/write from/to a static bank. If a read operation + is performed, the bank can be the same or a different + one, whereas it must be different in case of write + operation to the bank, except in muxed mode or mode + D. In some cases, whatever the programmed BUSTRUN + values, the bus turnaround delay is fixed as follows: + The bus turnaround delay is not inserted between two + consecutive asynchronous write transfers to the same + static memory bank except in muxed mode and mode D. + There is a bus turnaround delay of 1 FMC clock cycle + between: Two consecutive asynchronous read transfers + to the same static memory bank except for modes muxed + and D. An asynchronous read to an asynchronous or + synchronous write to any static bank or dynamic bank + except in modes muxed and D mode. There is a bus + turnaround delay of 2 FMC clock cycle between: Two + consecutive synchronous write operations (in Burst or + Single mode) to the same bank. A synchronous write + (burst or single) access and an asynchronous write or + read transfer to or from static memory bank (the bank + can be the same or a different one in case of a read + operation. Two consecutive synchronous read + operations (in Burst or Single mode) followed by any + synchronous/asynchronous read or write from/to + another static memory bank. There is a bus turnaround + delay of 3 FMC clock cycle between: Two consecutive + synchronous write operations (in Burst or Single + mode) to different static banks. A synchronous write + access (in Burst or Single mode) and a synchronous + read from the same or a different bank. The bus + turnaround delay allows to match the minimum time + between consecutive transactions (tEHEL from NEx high + to NEx low) and the maximum time required by the + memory to free the data bus after a read access + (tEHQZ): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin and (BUSTRUN + 2)KCK_FMC period &#8805; + tEHQZmax if EXTMOD = 0 (BUSTRUN + 2)KCK_FMC period + &#8805; max (tEHELmin, tEHQZmax) if EXTMOD = 126. + ... + 16 + 4 + + + CLKDIV + Clock divide ratio (for FMC_CLK signal) + These bits define the period of FMC_CLK clock output + signal, expressed in number of KCK_FMC cycles: In + asynchronous NOR Flash, SRAM or PSRAM accesses, this + value is dont care. Note: Refer to Section20.6.5: + Synchronous transactions for FMC_CLK divider ratio + formula) + 20 + 4 + + + DATLAT + Data latency for synchronous memory For + synchronous access with read write burst mode enabled + these bits define the number of memory clock + cycles + 24 + 4 + + + ACCMOD + Access mode These bits specify the + asynchronous access modes as shown in the timing + diagrams. They are taken into account only when the + EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BCR2 + BCR2 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories. + 0x8 + 0x20 + read-write + 0x000030D2 + + + MBKEN + Memory bank enable bit This bit enables + the memory bank. After reset Bank1 is enabled, all + others are disabled. Accessing a disabled bank causes + an ERROR on AXI bus. + 0 + 1 + + + MUXEN + Address/data multiplexing enable bit + When this bit is set, the address and data values are + multiplexed on the data bus, valid only with NOR and + PSRAM memories: + 1 + 1 + + + MTYP + Memory type These bits define the type + of external memory attached to the corresponding + memory bank: + 2 + 2 + + + MWID + Memory data bus width Defines the + external memory device width, valid for all type of + memories. + 4 + 2 + + + FACCEN + Flash access enable This bit enables NOR + Flash memory access operations. + 6 + 1 + + + BURSTEN + Burst enable bit This bit + enables/disables synchronous accesses during read + operations. It is valid only for synchronous memories + operating in Burst mode: + 8 + 1 + + + WAITPOL + Wait signal polarity bit This bit + defines the polarity of the wait signal from memory + used for either in synchronous or asynchronous + mode: + 9 + 1 + + + WAITCFG + Wait timing configuration The NWAIT + signal indicates whether the data from the memory are + valid or if a wait state must be inserted when + accessing the memory in synchronous mode. This + configuration bit determines if NWAIT is asserted by + the memory one clock cycle before the wait state or + during the wait state: + 11 + 1 + + + WREN + Write enable bit This bit indicates + whether write operations are enabled/disabled in the + bank by the FMC: + 12 + 1 + + + WAITEN + Wait enable bit This bit + enables/disables wait-state insertion via the NWAIT + signal when accessing the memory in synchronous + mode. + 13 + 1 + + + EXTMOD + Extended mode enable. This bit enables + the FMC to program the write timings for asynchronous + accesses inside the FMC_BWTR register, thus resulting + in different timings for read and write operations. + Note: When the extended mode is disabled, the FMC can + operate in Mode1 or Mode2 as follows: ** Mode 1 is + the default mode when the SRAM/PSRAM memory type is + selected (MTYP =0x0 or 0x01) ** Mode 2 is the default + mode when the NOR memory type is selected (MTYP = + 0x10). + 14 + 1 + + + ASYNCWAIT + Wait signal during asynchronous + transfers This bit enables/disables the FMC to use + the wait signal even during an asynchronous + protocol. + 15 + 1 + + + CPSIZE + CRAM Page Size These are used for + Cellular RAM 1.5 which does not allow burst access to + cross the address boundaries between pages. When + these bits are configured, the FMC controller splits + automatically the burst access when the memory page + size is reached (refer to memory datasheet for page + size). Other configuration: reserved. + 16 + 3 + + + CBURSTRW + Write burst enable For PSRAM (CRAM) + operating in Burst mode, the bit enables synchronous + accesses during write operations. The enable bit for + synchronous read accesses is the BURSTEN bit in the + FMC_BCRx register. + 19 + 1 + + + CCLKEN + Continuous Clock Enable This bit enables + the FMC_CLK clock output to external memory devices. + Note: The CCLKEN bit of the FMC_BCR2..4 registers is + dont care. It is only enabled through the FMC_BCR1 + register. Bank 1 must be configured in synchronous + mode to generate the FMC_CLK continuous clock. If + CCLKEN bit is set, the FMC_CLK clock ratio is + specified by CLKDIV value in the FMC_BTR1 register. + CLKDIV in FMC_BWTR1 is dont care. If the synchronous + mode is used and CCLKEN bit is set, the synchronous + memories connected to other banks than Bank 1 are + clocked by the same clock (the CLKDIV value in the + FMC_BTR2..4 and FMC_BWTR2..4 registers for other + banks has no effect.) + 20 + 1 + + + WFDIS + Write FIFO Disable This bit disables the + Write FIFO used by the FMC controller. Note: The + WFDIS bit of the FMC_BCR2..4 registers is dont care. + It is only enabled through the FMC_BCR1 + register. + 21 + 1 + + + BMAP + FMC bank mapping These bits allows + different to remap SDRAM bank2 or swap the FMC + NOR/PSRAM and SDRAM banks.Refer to Table 10 for Note: + The BMAP bits of the FMC_BCR2..4 registers are dont + care. It is only enabled through the FMC_BCR1 + register. + 24 + 2 + + + FMCEN + FMC controller Enable This bit + enables/disables the FMC controller. Note: The FMCEN + bit of the FMC_BCR2..4 registers is dont care. It is + only enabled through the FMC_BCR1 + register. + 31 + 1 + + + + + BTR2 + BTR2 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories.If the EXTMOD bit is set in the + FMC_BCRx register, then this register is partitioned for + write and read access, that is, 2 registers are + available: one to configure read accesses (this register) + and one to configure write accesses (FMC_BWTRx + registers). + 0xC + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration These bits + are written by software to define the duration of the + address setup phase (refer to Figure81 to Figure93), + used in SRAMs, ROMs and asynchronous NOR Flash: For + each access mode address setup phase duration, please + refer to the respective figure (refer to Figure81 to + Figure93). Note: In synchronous accesses, this value + is dont care. In Muxed mode or Mode D, the minimum + value for ADDSET is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in mode D or multiplexed accesses: For each + access mode address-hold phase duration, please refer + to the respective figure (Figure81 to Figure93). + Note: In synchronous accesses, this value is not + used, the address hold phase is always 1 memory clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous accesses: For each memory type and + access mode data-phase duration, please refer to the + respective figure (Figure81 to Figure93). Example: + Mode1, write access, DATAST=1: Data-phase duration= + DATAST+1 = 2 KCK_FMC clock cycles. Note: In + synchronous accesses, this value is dont + care. + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write-to-read or read-to write transaction. The + programmed bus turnaround delay is inserted between + an asynchronous read (in muxed or mode D) or write + transaction and any other asynchronous /synchronous + read/write from/to a static bank. If a read operation + is performed, the bank can be the same or a different + one, whereas it must be different in case of write + operation to the bank, except in muxed mode or mode + D. In some cases, whatever the programmed BUSTRUN + values, the bus turnaround delay is fixed as follows: + The bus turnaround delay is not inserted between two + consecutive asynchronous write transfers to the same + static memory bank except in muxed mode and mode D. + There is a bus turnaround delay of 1 FMC clock cycle + between: Two consecutive asynchronous read transfers + to the same static memory bank except for modes muxed + and D. An asynchronous read to an asynchronous or + synchronous write to any static bank or dynamic bank + except in modes muxed and D mode. There is a bus + turnaround delay of 2 FMC clock cycle between: Two + consecutive synchronous write operations (in Burst or + Single mode) to the same bank. A synchronous write + (burst or single) access and an asynchronous write or + read transfer to or from static memory bank (the bank + can be the same or a different one in case of a read + operation. Two consecutive synchronous read + operations (in Burst or Single mode) followed by any + synchronous/asynchronous read or write from/to + another static memory bank. There is a bus turnaround + delay of 3 FMC clock cycle between: Two consecutive + synchronous write operations (in Burst or Single + mode) to different static banks. A synchronous write + access (in Burst or Single mode) and a synchronous + read from the same or a different bank. The bus + turnaround delay allows to match the minimum time + between consecutive transactions (tEHEL from NEx high + to NEx low) and the maximum time required by the + memory to free the data bus after a read access + (tEHQZ): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin and (BUSTRUN + 2)KCK_FMC period &#8805; + tEHQZmax if EXTMOD = 0 (BUSTRUN + 2)KCK_FMC period + &#8805; max (tEHELmin, tEHQZmax) if EXTMOD = 1. + ... + 16 + 4 + + + CLKDIV + Clock divide ratio (for FMC_CLK signal) + These bits define the period of FMC_CLK clock output + signal, expressed in number of KCK_FMC cycles: In + asynchronous NOR Flash, SRAM or PSRAM accesses, this + value is dont care. Note: Refer to Section20.6.5: + Synchronous transactions for FMC_CLK divider ratio + formula) + 20 + 4 + + + DATLAT + Data latency for synchronous memory For + synchronous access with read write burst mode enabled + these bits define the number of memory clock + cycles + 24 + 4 + + + ACCMOD + Access mode These bits specify the + asynchronous access modes as shown in the timing + diagrams. They are taken into account only when the + EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BCR3 + BCR3 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories. + 0x10 + 0x20 + read-write + 0x000030D2 + + + MBKEN + Memory bank enable bit This bit enables + the memory bank. After reset Bank1 is enabled, all + others are disabled. Accessing a disabled bank causes + an ERROR on AXI bus. + 0 + 1 + + + MUXEN + Address/data multiplexing enable bit + When this bit is set, the address and data values are + multiplexed on the data bus, valid only with NOR and + PSRAM memories: + 1 + 1 + + + MTYP + Memory type These bits define the type + of external memory attached to the corresponding + memory bank: + 2 + 2 + + + MWID + Memory data bus width Defines the + external memory device width, valid for all type of + memories. + 4 + 2 + + + FACCEN + Flash access enable This bit enables NOR + Flash memory access operations. + 6 + 1 + + + BURSTEN + Burst enable bit This bit + enables/disables synchronous accesses during read + operations. It is valid only for synchronous memories + operating in Burst mode: + 8 + 1 + + + WAITPOL + Wait signal polarity bit This bit + defines the polarity of the wait signal from memory + used for either in synchronous or asynchronous + mode: + 9 + 1 + + + WAITCFG + Wait timing configuration The NWAIT + signal indicates whether the data from the memory are + valid or if a wait state must be inserted when + accessing the memory in synchronous mode. This + configuration bit determines if NWAIT is asserted by + the memory one clock cycle before the wait state or + during the wait state: + 11 + 1 + + + WREN + Write enable bit This bit indicates + whether write operations are enabled/disabled in the + bank by the FMC: + 12 + 1 + + + WAITEN + Wait enable bit This bit + enables/disables wait-state insertion via the NWAIT + signal when accessing the memory in synchronous + mode. + 13 + 1 + + + EXTMOD + Extended mode enable. This bit enables + the FMC to program the write timings for asynchronous + accesses inside the FMC_BWTR register, thus resulting + in different timings for read and write operations. + Note: When the extended mode is disabled, the FMC can + operate in Mode1 or Mode2 as follows: ** Mode 1 is + the default mode when the SRAM/PSRAM memory type is + selected (MTYP =0x0 or 0x01) ** Mode 2 is the default + mode when the NOR memory type is selected (MTYP = + 0x10). + 14 + 1 + + + ASYNCWAIT + Wait signal during asynchronous + transfers This bit enables/disables the FMC to use + the wait signal even during an asynchronous + protocol. + 15 + 1 + + + CPSIZE + CRAM Page Size These are used for + Cellular RAM 1.5 which does not allow burst access to + cross the address boundaries between pages. When + these bits are configured, the FMC controller splits + automatically the burst access when the memory page + size is reached (refer to memory datasheet for page + size). Other configuration: reserved. + 16 + 3 + + + CBURSTRW + Write burst enable For PSRAM (CRAM) + operating in Burst mode, the bit enables synchronous + accesses during write operations. The enable bit for + synchronous read accesses is the BURSTEN bit in the + FMC_BCRx register. + 19 + 1 + + + CCLKEN + Continuous Clock Enable This bit enables + the FMC_CLK clock output to external memory devices. + Note: The CCLKEN bit of the FMC_BCR2..4 registers is + dont care. It is only enabled through the FMC_BCR1 + register. Bank 1 must be configured in synchronous + mode to generate the FMC_CLK continuous clock. If + CCLKEN bit is set, the FMC_CLK clock ratio is + specified by CLKDIV value in the FMC_BTR1 register. + CLKDIV in FMC_BWTR1 is dont care. If the synchronous + mode is used and CCLKEN bit is set, the synchronous + memories connected to other banks than Bank 1 are + clocked by the same clock (the CLKDIV value in the + FMC_BTR2..4 and FMC_BWTR2..4 registers for other + banks has no effect.) + 20 + 1 + + + WFDIS + Write FIFO Disable This bit disables the + Write FIFO used by the FMC controller. Note: The + WFDIS bit of the FMC_BCR2..4 registers is dont care. + It is only enabled through the FMC_BCR1 + register. + 21 + 1 + + + BMAP + FMC bank mapping These bits allows + different to remap SDRAM bank2 or swap the FMC + NOR/PSRAM and SDRAM banks.Refer to Table 10 for Note: + The BMAP bits of the FMC_BCR2..4 registers are dont + care. It is only enabled through the FMC_BCR1 + register. + 24 + 2 + + + FMCEN + FMC controller Enable This bit + enables/disables the FMC controller. Note: The FMCEN + bit of the FMC_BCR2..4 registers is dont care. It is + only enabled through the FMC_BCR1 + register. + 31 + 1 + + + + + BTR3 + BTR3 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories.If the EXTMOD bit is set in the + FMC_BCRx register, then this register is partitioned for + write and read access, that is, 2 registers are + available: one to configure read accesses (this register) + and one to configure write accesses (FMC_BWTRx + registers). + 0x14 + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration These bits + are written by software to define the duration of the + address setup phase (refer to Figure81 to Figure93), + used in SRAMs, ROMs and asynchronous NOR Flash: For + each access mode address setup phase duration, please + refer to the respective figure (refer to Figure81 to + Figure93). Note: In synchronous accesses, this value + is dont care. In Muxed mode or Mode D, the minimum + value for ADDSET is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in mode D or multiplexed accesses: For each + access mode address-hold phase duration, please refer + to the respective figure (Figure81 to Figure93). + Note: In synchronous accesses, this value is not + used, the address hold phase is always 1 memory clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous accesses: For each memory type and + access mode data-phase duration, please refer to the + respective figure (Figure81 to Figure93). Example: + Mode1, write access, DATAST=1: Data-phase duration= + DATAST+1 = 2 KCK_FMC clock cycles. Note: In + synchronous accesses, this value is dont + care. + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write-to-read or read-to write transaction. The + programmed bus turnaround delay is inserted between + an asynchronous read (in muxed or mode D) or write + transaction and any other asynchronous /synchronous + read/write from/to a static bank. If a read operation + is performed, the bank can be the same or a different + one, whereas it must be different in case of write + operation to the bank, except in muxed mode or mode + D. In some cases, whatever the programmed BUSTRUN + values, the bus turnaround delay is fixed as follows: + The bus turnaround delay is not inserted between two + consecutive asynchronous write transfers to the same + static memory bank except in muxed mode and mode D. + There is a bus turnaround delay of 1 FMC clock cycle + between: Two consecutive asynchronous read transfers + to the same static memory bank except for modes muxed + and D. An asynchronous read to an asynchronous or + synchronous write to any static bank or dynamic bank + except in modes muxed and D mode. There is a bus + turnaround delay of 2 FMC clock cycle between: Two + consecutive synchronous write operations (in Burst or + Single mode) to the same bank. A synchronous write + (burst or single) access and an asynchronous write or + read transfer to or from static memory bank (the bank + can be the same or a different one in case of a read + operation. Two consecutive synchronous read + operations (in Burst or Single mode) followed by any + synchronous/asynchronous read or write from/to + another static memory bank. There is a bus turnaround + delay of 3 FMC clock cycle between: Two consecutive + synchronous write operations (in Burst or Single + mode) to different static banks. A synchronous write + access (in Burst or Single mode) and a synchronous + read from the same or a different bank. The bus + turnaround delay allows to match the minimum time + between consecutive transactions (tEHEL from NEx high + to NEx low) and the maximum time required by the + memory to free the data bus after a read access + (tEHQZ): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin and (BUSTRUN + 2)KCK_FMC period &#8805; + tEHQZmax if EXTMOD = 0 (BUSTRUN + 2)KCK_FMC period + &#8805; max (tEHELmin, tEHQZmax) if EXTMOD =1. + ... + 16 + 4 + + + CLKDIV + Clock divide ratio (for FMC_CLK signal) + These bits define the period of FMC_CLK clock output + signal, expressed in number of KCK_FMC cycles: In + asynchronous NOR Flash, SRAM or PSRAM accesses, this + value is dont care. Note: Refer to Section20.6.5: + Synchronous transactions for FMC_CLK divider ratio + formula) + 20 + 4 + + + DATLAT + Data latency for synchronous memory For + synchronous access with read write burst mode enabled + these bits define the number of memory clock + cycles + 24 + 4 + + + ACCMOD + Access mode These bits specify the + asynchronous access modes as shown in the timing + diagrams. They are taken into account only when the + EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BCR4 + BCR4 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories. + 0x18 + 0x20 + read-write + 0x000030D2 + + + MBKEN + Memory bank enable bit This bit enables + the memory bank. After reset Bank1 is enabled, all + others are disabled. Accessing a disabled bank causes + an ERROR on AXI bus. + 0 + 1 + + + MUXEN + Address/data multiplexing enable bit + When this bit is set, the address and data values are + multiplexed on the data bus, valid only with NOR and + PSRAM memories: + 1 + 1 + + + MTYP + Memory type These bits define the type + of external memory attached to the corresponding + memory bank: + 2 + 2 + + + MWID + Memory data bus width Defines the + external memory device width, valid for all type of + memories. + 4 + 2 + + + FACCEN + Flash access enable This bit enables NOR + Flash memory access operations. + 6 + 1 + + + BURSTEN + Burst enable bit This bit + enables/disables synchronous accesses during read + operations. It is valid only for synchronous memories + operating in Burst mode: + 8 + 1 + + + WAITPOL + Wait signal polarity bit This bit + defines the polarity of the wait signal from memory + used for either in synchronous or asynchronous + mode: + 9 + 1 + + + WAITCFG + Wait timing configuration The NWAIT + signal indicates whether the data from the memory are + valid or if a wait state must be inserted when + accessing the memory in synchronous mode. This + configuration bit determines if NWAIT is asserted by + the memory one clock cycle before the wait state or + during the wait state: + 11 + 1 + + + WREN + Write enable bit This bit indicates + whether write operations are enabled/disabled in the + bank by the FMC: + 12 + 1 + + + WAITEN + Wait enable bit This bit + enables/disables wait-state insertion via the NWAIT + signal when accessing the memory in synchronous + mode. + 13 + 1 + + + EXTMOD + Extended mode enable. This bit enables + the FMC to program the write timings for asynchronous + accesses inside the FMC_BWTR register, thus resulting + in different timings for read and write operations. + Note: When the extended mode is disabled, the FMC can + operate in Mode1 or Mode2 as follows: ** Mode 1 is + the default mode when the SRAM/PSRAM memory type is + selected (MTYP =0x0 or 0x01) ** Mode 2 is the default + mode when the NOR memory type is selected (MTYP = + 0x10). + 14 + 1 + + + ASYNCWAIT + Wait signal during asynchronous + transfers This bit enables/disables the FMC to use + the wait signal even during an asynchronous + protocol. + 15 + 1 + + + CPSIZE + CRAM Page Size These are used for + Cellular RAM 1.5 which does not allow burst access to + cross the address boundaries between pages. When + these bits are configured, the FMC controller splits + automatically the burst access when the memory page + size is reached (refer to memory datasheet for page + size). Other configuration: reserved. + 16 + 3 + + + CBURSTRW + Write burst enable For PSRAM (CRAM) + operating in Burst mode, the bit enables synchronous + accesses during write operations. The enable bit for + synchronous read accesses is the BURSTEN bit in the + FMC_BCRx register. + 19 + 1 + + + CCLKEN + Continuous Clock Enable This bit enables + the FMC_CLK clock output to external memory devices. + Note: The CCLKEN bit of the FMC_BCR2..4 registers is + dont care. It is only enabled through the FMC_BCR1 + register. Bank 1 must be configured in synchronous + mode to generate the FMC_CLK continuous clock. If + CCLKEN bit is set, the FMC_CLK clock ratio is + specified by CLKDIV value in the FMC_BTR1 register. + CLKDIV in FMC_BWTR1 is dont care. If the synchronous + mode is used and CCLKEN bit is set, the synchronous + memories connected to other banks than Bank 1 are + clocked by the same clock (the CLKDIV value in the + FMC_BTR2..4 and FMC_BWTR2..4 registers for other + banks has no effect.) + 20 + 1 + + + WFDIS + Write FIFO Disable This bit disables the + Write FIFO used by the FMC controller. Note: The + WFDIS bit of the FMC_BCR2..4 registers is dont care. + It is only enabled through the FMC_BCR1 + register. + 21 + 1 + + + BMAP + FMC bank mapping These bits allows + different to remap SDRAM bank2 or swap the FMC + NOR/PSRAM and SDRAM banks.Refer to Table 10 for Note: + The BMAP bits of the FMC_BCR2..4 registers are dont + care. It is only enabled through the FMC_BCR1 + register. + 24 + 2 + + + FMCEN + FMC controller Enable This bit + enables/disables the FMC controller. Note: The FMCEN + bit of the FMC_BCR2..4 registers is dont care. It is + only enabled through the FMC_BCR1 + register. + 31 + 1 + + + + + BTR4 + BTR4 + This register contains the control + information of each memory bank, used for SRAMs, PSRAM + and NOR Flash memories.If the EXTMOD bit is set in the + FMC_BCRx register, then this register is partitioned for + write and read access, that is, 2 registers are + available: one to configure read accesses (this register) + and one to configure write accesses (FMC_BWTRx + registers). + 0x1C + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration These bits + are written by software to define the duration of the + address setup phase (refer to Figure81 to Figure93), + used in SRAMs, ROMs and asynchronous NOR Flash: For + each access mode address setup phase duration, please + refer to the respective figure (refer to Figure81 to + Figure93). Note: In synchronous accesses, this value + is dont care. In Muxed mode or Mode D, the minimum + value for ADDSET is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in mode D or multiplexed accesses: For each + access mode address-hold phase duration, please refer + to the respective figure (Figure81 to Figure93). + Note: In synchronous accesses, this value is not + used, the address hold phase is always 1 memory clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous accesses: For each memory type and + access mode data-phase duration, please refer to the + respective figure (Figure81 to Figure93). Example: + Mode1, write access, DATAST=1: Data-phase duration= + DATAST+1 = 2 KCK_FMC clock cycles. Note: In + synchronous accesses, this value is dont + care. + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write-to-read or read-to write transaction. The + programmed bus turnaround delay is inserted between + an asynchronous read (in muxed or mode D) or write + transaction and any other asynchronous /synchronous + read/write from/to a static bank. If a read operation + is performed, the bank can be the same or a different + one, whereas it must be different in case of write + operation to the bank, except in muxed mode or mode + D. In some cases, whatever the programmed BUSTRUN + values, the bus turnaround delay is fixed as follows: + The bus turnaround delay is not inserted between two + consecutive asynchronous write transfers to the same + static memory bank except in muxed mode and mode D. + There is a bus turnaround delay of 1 FMC clock cycle + between: Two consecutive asynchronous read transfers + to the same static memory bank except for modes muxed + and D. An asynchronous read to an asynchronous or + synchronous write to any static bank or dynamic bank + except in modes muxed and D mode. There is a bus + turnaround delay of 2 FMC clock cycle between: Two + consecutive synchronous write operations (in Burst or + Single mode) to the same bank. A synchronous write + (burst or single) access and an asynchronous write or + read transfer to or from static memory bank (the bank + can be the same or a different one in case of a read + operation. Two consecutive synchronous read + operations (in Burst or Single mode) followed by any + synchronous/asynchronous read or write from/to + another static memory bank. There is a bus turnaround + delay of 3 FMC clock cycle between: Two consecutive + synchronous write operations (in Burst or Single + mode) to different static banks. A synchronous write + access (in Burst or Single mode) and a synchronous + read from the same or a different bank. The bus + turnaround delay allows to match the minimum time + between consecutive transactions (tEHEL from NEx high + to NEx low) and the maximum time required by the + memory to free the data bus after a read access + (tEHQZ): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin and (BUSTRUN + 2)KCK_FMC period &#8805; + tEHQZmax if EXTMOD = 0 (BUSTRUN + 2)KCK_FMC period + &#8805; max (tEHELmin, tEHQZmax) if EXTMOD =1. + ... + 16 + 4 + + + CLKDIV + Clock divide ratio (for FMC_CLK signal) + These bits define the period of FMC_CLK clock output + signal, expressed in number of KCK_FMC cycles: In + asynchronous NOR Flash, SRAM or PSRAM accesses, this + value is dont care. Note: Refer to Section20.6.5: + Synchronous transactions for FMC_CLK divider ratio + formula) + 20 + 4 + + + DATLAT + Data latency for synchronous memory For + synchronous access with read write burst mode enabled + these bits define the number of memory clock + cycles + 24 + 4 + + + ACCMOD + Access mode These bits specify the + asynchronous access modes as shown in the timing + diagrams. They are taken into account only when the + EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + PCR + PCR + NAND Flash control registers + 0x80 + 0x20 + read-write + 0x00000018 + + + PWAITEN + Wait feature enable bit. This bit + enables the Wait feature for the NAND Flash memory + bank: + 1 + 1 + + + PBKEN + NAND Flash memory bank enable bit. This + bit enables the memory bank. Accessing a disabled + memory bank causes an ERROR on AXI bus + 2 + 1 + + + PWID + Data bus width. These bits define the + external memory device width. + 4 + 2 + + + ECCEN + ECC computation logic enable + bit + 6 + 1 + + + TCLR + CLE to RE delay. These bits set time + from CLE low to RE low in number of KCK_FMC clock + cycles. The time is give by the following formula: + t_clr = (TCLR + SET + 2) TKCK_FMC where TKCK_FMC is + the KCK_FMC clock period Note: Set is MEMSET or + ATTSET according to the addressed + space. + 9 + 4 + + + TAR + ALE to RE delay. These bits set time + from ALE low to RE low in number of KCK_FMC clock + cycles. Time is: t_ar = (TAR + SET + 2) TKCK_FMC + where TKCK_FMC is the FMC clock period Note: Set is + MEMSET or ATTSET according to the addressed + space. + 13 + 4 + + + ECCPS + ECC page size. These bits define the + page size for the extended ECC: + 17 + 3 + + + + + SR + SR + This register contains information about the + FIFO status and interrupt. The FMC features a FIFO that + is used when writing to memories to transfer up to 16 + words of data.This is used to quickly write to the FIFO + and free the AXI bus for transactions to peripherals + other than the FMC, while the FMC is draining its FIFO + into the memory. One of these register bits indicates the + status of the FIFO, for ECC purposes.The ECC is + calculated while the data are written to the memory. To + read the correct ECC, the software must consequently wait + until the FIFO is empty. + 0x84 + 0x20 + 0x00000040 + + + IRS + Interrupt rising edge status The flag is + set by hardware and reset by software. Note: If this + bit is written by software to 1 it will be + set. + 0 + 1 + read-write + + + ILS + Interrupt high-level status The flag is + set by hardware and reset by software. + 1 + 1 + read-write + + + IFS + Interrupt falling edge status The flag + is set by hardware and reset by software. Note: If + this bit is written by software to 1 it will be + set. + 2 + 1 + read-write + + + IREN + Interrupt rising edge detection enable + bit + 3 + 1 + read-write + + + ILEN + Interrupt high-level detection enable + bit + 4 + 1 + read-write + + + IFEN + Interrupt falling edge detection enable + bit + 5 + 1 + read-write + + + FEMPT + FIFO empty. Read-only bit that provides + the status of the FIFO + 6 + 1 + read-only + + + + + PMEM + PMEM + The FMC_PMEM read/write register contains + the timing information for NAND Flash memory bank. This + information is used to access either the common memory + space of the NAND Flash for command, address write access + and data read/write access. + 0x88 + 0x20 + read-write + 0xFCFCFCFC + + + MEMSET + Common memory x setup time These bits + define the number of KCK_FMC (+1) clock cycles to set + up the address before the command assertion (NWE, + NOE), for NAND Flash read or write access to common + memory space: + 0 + 8 + + + MEMWAIT + Common memory wait time These bits + define the minimum number of KCK_FMC (+1) clock + cycles to assert the command (NWE, NOE), for NAND + Flash read or write access to common memory space. + The duration of command assertion is extended if the + wait signal (NWAIT) is active (low) at the end of the + programmed value of KCK_FMC: + 8 + 8 + + + MEMHOLD + Common memory hold time These bits + define the number of KCK_FMC clock cycles for write + accesses and KCK_FMC+1 clock cycles for read accesses + during which the address is held (and data for write + accesses) after the command is de-asserted (NWE, + NOE), for NAND Flash read or write access to common + memory space: + 16 + 8 + + + MEMHIZ + Common memory x data bus Hi-Z time These + bits define the number of KCK_FMC clock cycles during + which the data bus is kept Hi-Z after the start of a + NAND Flash write access to common memory space. This + is only valid for write transactions: + 24 + 8 + + + + + PATT + PATT + The FMC_PATT read/write register contains + the timing information for NAND Flash memory bank. It is + used for 8-bit accesses to the attribute memory space of + the NAND Flash for the last address write access if the + timing must differ from that of previous accesses (for + Ready/Busy management, refer to Section20.8.5: NAND Flash + prewait feature). + 0x8C + 0x20 + read-write + 0xFCFCFCFC + + + ATTSET + Attribute memory setup time These bits + define the number of KCK_FMC (+1) clock cycles to set + up address before the command assertion (NWE, NOE), + for NAND Flash read or write access to attribute + memory space: + 0 + 8 + + + ATTWAIT + Attribute memory wait time These bits + define the minimum number of x KCK_FMC (+1) clock + cycles to assert the command (NWE, NOE), for NAND + Flash read or write access to attribute memory space. + The duration for command assertion is extended if the + wait signal (NWAIT) is active (low) at the end of the + programmed value of KCK_FMC: + 8 + 8 + + + ATTHOLD + Attribute memory hold time These bits + define the number of KCK_FMC clock cycles during + which the address is held (and data for write access) + after the command de-assertion (NWE, NOE), for NAND + Flash read or write access to attribute memory + space: + 16 + 8 + + + ATTHIZ + Attribute memory data bus Hi-Z time + These bits define the number of KCK_FMC clock cycles + during which the data bus is kept in Hi-Z after the + start of a NAND Flash write access to attribute + memory space on socket. Only valid for writ + transaction: + 24 + 8 + + + + + ECCR + ECCR + This register contain the current error + correction code value computed by the ECC computation + modules of the FMC NAND controller. When the CPU + reads/writes the data from a NAND Flash memory page at + the correct address (refer to Section20.8.6: Computation + of the error correction code (ECC) in NAND Flash memory), + the data read/written from/to the NAND Flash memory are + processed automatically by the ECC computation module. + When X bytes have been read (according to the ECCPS field + in the FMC_PCR registers), the CPU must read the computed + ECC value from the FMC_ECC registers. It then verifies if + these computed parity data are the same as the parity + value recorded in the spare area, to determine whether a + page is valid, and, to correct it otherwise. The FMC_ECCR + register should be cleared after being read by setting + the ECCEN bit to 0. To compute a new data block, the + ECCEN bit must be set to 1. + 0x94 + 0x20 + read-only + 0x00000000 + + + ECC + ECC result This field contains the value + computed by the ECC computation logic. Table167 + describes the contents of these bit + fields. + 0 + 32 + + + + + BWTR1 + BWTR1 + This register contains the control + information of each memory bank. It is used for SRAMs, + PSRAMs and NOR Flash memories. When the EXTMOD bit is set + in the FMC_BCRx register, then this register is active + for write access. + 0x104 + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration. These bits + are written by software to define the duration of the + address setup phase in KCK_FMC cycles (refer to + Figure81 to Figure93), used in asynchronous accesses: + ... Note: In synchronous accesses, this value is not + used, the address setup phase is always 1 Flash clock + period duration. In muxed mode, the minimum ADDSET + value is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration. These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in asynchronous multiplexed accesses: ... Note: + In synchronous NOR Flash accesses, this value is not + used, the address hold phase is always 1 Flash clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration. These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous SRAM, PSRAM and NOR Flash memory + accesses: + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write transaction to match the minimum time between + consecutive transactions (tEHEL from ENx high to ENx + low): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin. The programmed bus turnaround delay is + inserted between a an asynchronous write transfer and + any other asynchronous /synchronous read or write + transfer to or from a static bank. If a read + operation is performed, the bank can be the same or a + different one, whereas it must be different in case + of write operation to the bank, except in muxed mode + or mode D. In some cases, whatever the programmed + BUSTRUN values, the bus turnaround delay is fixed as + follows: The bus turnaround delay is not inserted + between two consecutive asynchronous write transfers + to the same static memory bank except for muxed mode + and mode D. There is a bus turnaround delay of 2 FMC + clock cycle between: Two consecutive synchronous + write operations (in Burst or Single mode) to the + same bank A synchronous write transfer ((in Burst or + Single mode) and an asynchronous write or read + transfer to or from static memory bank. There is a + bus turnaround delay of 3 FMC clock cycle between: + Two consecutive synchronous write operations (in + Burst or Single mode) to different static banks. A + synchronous write transfer (in Burst or Single mode) + and a synchronous read from the same or a different + bank. ... + 16 + 4 + + + ACCMOD + Access mode. These bits specify the + asynchronous access modes as shown in the next timing + diagrams.These bits are taken into account only when + the EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BWTR2 + BWTR2 + This register contains the control + information of each memory bank. It is used for SRAMs, + PSRAMs and NOR Flash memories. When the EXTMOD bit is set + in the FMC_BCRx register, then this register is active + for write access. + 0x10C + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration. These bits + are written by software to define the duration of the + address setup phase in KCK_FMC cycles (refer to + Figure81 to Figure93), used in asynchronous accesses: + ... Note: In synchronous accesses, this value is not + used, the address setup phase is always 1 Flash clock + period duration. In muxed mode, the minimum ADDSET + value is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration. These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in asynchronous multiplexed accesses: ... Note: + In synchronous NOR Flash accesses, this value is not + used, the address hold phase is always 1 Flash clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration. These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous SRAM, PSRAM and NOR Flash memory + accesses: + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write transaction to match the minimum time between + consecutive transactions (tEHEL from ENx high to ENx + low): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin. The programmed bus turnaround delay is + inserted between a an asynchronous write transfer and + any other asynchronous /synchronous read or write + transfer to or from a static bank. If a read + operation is performed, the bank can be the same or a + different one, whereas it must be different in case + of write operation to the bank, except in muxed mode + or mode D. In some cases, whatever the programmed + BUSTRUN values, the bus turnaround delay is fixed as + follows: The bus turnaround delay is not inserted + between two consecutive asynchronous write transfers + to the same static memory bank except for muxed mode + and mode D. There is a bus turnaround delay of 2 FMC + clock cycle between: Two consecutive synchronous + write operations (in Burst or Single mode) to the + same bank A synchronous write transfer ((in Burst or + Single mode) and an asynchronous write or read + transfer to or from static memory bank. There is a + bus turnaround delay of 3 FMC clock cycle between: + Two consecutive synchronous write operations (in + Burst or Single mode) to different static banks. A + synchronous write transfer (in Burst or Single mode) + and a synchronous read from the same or a different + bank. ... + 16 + 4 + + + ACCMOD + Access mode. These bits specify the + asynchronous access modes as shown in the next timing + diagrams.These bits are taken into account only when + the EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BWTR3 + BWTR3 + This register contains the control + information of each memory bank. It is used for SRAMs, + PSRAMs and NOR Flash memories. When the EXTMOD bit is set + in the FMC_BCRx register, then this register is active + for write access. + 0x114 + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration. These bits + are written by software to define the duration of the + address setup phase in KCK_FMC cycles (refer to + Figure81 to Figure93), used in asynchronous accesses: + ... Note: In synchronous accesses, this value is not + used, the address setup phase is always 1 Flash clock + period duration. In muxed mode, the minimum ADDSET + value is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration. These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in asynchronous multiplexed accesses: ... Note: + In synchronous NOR Flash accesses, this value is not + used, the address hold phase is always 1 Flash clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration. These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous SRAM, PSRAM and NOR Flash memory + accesses: + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write transaction to match the minimum time between + consecutive transactions (tEHEL from ENx high to ENx + low): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin. The programmed bus turnaround delay is + inserted between a an asynchronous write transfer and + any other asynchronous /synchronous read or write + transfer to or from a static bank. If a read + operation is performed, the bank can be the same or a + different one, whereas it must be different in case + of write operation to the bank, except in muxed mode + or mode D. In some cases, whatever the programmed + BUSTRUN values, the bus turnaround delay is fixed as + follows: The bus turnaround delay is not inserted + between two consecutive asynchronous write transfers + to the same static memory bank except for muxed mode + and mode D. There is a bus turnaround delay of 2 FMC + clock cycle between: Two consecutive synchronous + write operations (in Burst or Single mode) to the + same bank A synchronous write transfer ((in Burst or + Single mode) and an asynchronous write or read + transfer to or from static memory bank. There is a + bus turnaround delay of 3 FMC clock cycle between: + Two consecutive synchronous write operations (in + Burst or Single mode) to different static banks. A + synchronous write transfer (in Burst or Single mode) + and a synchronous read from the same or a different + bank. ... + 16 + 4 + + + ACCMOD + Access mode. These bits specify the + asynchronous access modes as shown in the next timing + diagrams.These bits are taken into account only when + the EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + BWTR4 + BWTR4 + This register contains the control + information of each memory bank. It is used for SRAMs, + PSRAMs and NOR Flash memories. When the EXTMOD bit is set + in the FMC_BCRx register, then this register is active + for write access. + 0x11C + 0x20 + read-write + 0x0FFFFFFF + + + ADDSET + Address setup phase duration. These bits + are written by software to define the duration of the + address setup phase in KCK_FMC cycles (refer to + Figure81 to Figure93), used in asynchronous accesses: + ... Note: In synchronous accesses, this value is not + used, the address setup phase is always 1 Flash clock + period duration. In muxed mode, the minimum ADDSET + value is 1. + 0 + 4 + + + ADDHLD + Address-hold phase duration. These bits + are written by software to define the duration of the + address hold phase (refer to Figure81 to Figure93), + used in asynchronous multiplexed accesses: ... Note: + In synchronous NOR Flash accesses, this value is not + used, the address hold phase is always 1 Flash clock + period duration. + 4 + 4 + + + DATAST + Data-phase duration. These bits are + written by software to define the duration of the + data phase (refer to Figure81 to Figure93), used in + asynchronous SRAM, PSRAM and NOR Flash memory + accesses: + 8 + 8 + + + BUSTURN + Bus turnaround phase duration These bits + are written by software to add a delay at the end of + a write transaction to match the minimum time between + consecutive transactions (tEHEL from ENx high to ENx + low): (BUSTRUN + 1) KCK_FMC period &#8805; + tEHELmin. The programmed bus turnaround delay is + inserted between a an asynchronous write transfer and + any other asynchronous /synchronous read or write + transfer to or from a static bank. If a read + operation is performed, the bank can be the same or a + different one, whereas it must be different in case + of write operation to the bank, except in muxed mode + or mode D. In some cases, whatever the programmed + BUSTRUN values, the bus turnaround delay is fixed as + follows: The bus turnaround delay is not inserted + between two consecutive asynchronous write transfers + to the same static memory bank except for muxed mode + and mode D. There is a bus turnaround delay of 2 FMC + clock cycle between: Two consecutive synchronous + write operations (in Burst or Single mode) to the + same bank A synchronous write transfer ((in Burst or + Single mode) and an asynchronous write or read + transfer to or from static memory bank. There is a + bus turnaround delay of 3 FMC clock cycle between: + Two consecutive synchronous write operations (in + Burst or Single mode) to different static banks. A + synchronous write transfer (in Burst or Single mode) + and a synchronous read from the same or a different + bank. ... + 16 + 4 + + + ACCMOD + Access mode. These bits specify the + asynchronous access modes as shown in the next timing + diagrams.These bits are taken into account only when + the EXTMOD bit in the FMC_BCRx register is + 1. + 28 + 2 + + + + + SDCR1 + SDCR1 + This register contains the control + parameters for each SDRAM memory bank + 0x140 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address bits These bits + define the number of bits of a column + address. + 0 + 2 + + + NR + Number of row address bits These bits + define the number of bits of a row + address. + 2 + 2 + + + MWID + Memory data bus width. These bits define + the memory device width. + 4 + 2 + + + NB + Number of internal banks This bit sets + the number of internal banks. + 6 + 1 + + + CAS + CAS Latency This bits sets the SDRAM CAS + latency in number of memory clock + cycles + 7 + 2 + + + WP + Write protection This bit enables write + mode access to the SDRAM bank. + 9 + 1 + + + SDCLK + SDRAM clock configuration These bits + define the SDRAM clock period for both SDRAM banks + and allow disabling the clock before changing the + frequency. In this case the SDRAM must be + re-initialized. Note: The corresponding bits in the + FMC_SDCR2 register is read only. + 10 + 2 + + + RBURST + Burst read This bit enables burst read + mode. The SDRAM controller anticipates the next read + commands during the CAS latency and stores data in + the Read FIFO. Note: The corresponding bit in the + FMC_SDCR2 register is read only. + 12 + 1 + + + RPIPE + Read pipe These bits define the delay, + in KCK_FMC clock cycles, for reading data after CAS + latency. Note: The corresponding bits in the + FMC_SDCR2 register is read only. + 13 + 2 + + + + + SDCR2 + SDCR2 + This register contains the control + parameters for each SDRAM memory bank + 0x144 + 0x20 + read-write + 0x000002D0 + + + NC + Number of column address bits These bits + define the number of bits of a column + address. + 0 + 2 + + + NR + Number of row address bits These bits + define the number of bits of a row + address. + 2 + 2 + + + MWID + Memory data bus width. These bits define + the memory device width. + 4 + 2 + + + NB + Number of internal banks This bit sets + the number of internal banks. + 6 + 1 + + + CAS + CAS Latency This bits sets the SDRAM CAS + latency in number of memory clock + cycles + 7 + 2 + + + WP + Write protection This bit enables write + mode access to the SDRAM bank. + 9 + 1 + + + SDCLK + SDRAM clock configuration These bits + define the SDRAM clock period for both SDRAM banks + and allow disabling the clock before changing the + frequency. In this case the SDRAM must be + re-initialized. Note: The corresponding bits in the + FMC_SDCR2 register is read only. + 10 + 2 + + + RBURST + Burst read This bit enables burst read + mode. The SDRAM controller anticipates the next read + commands during the CAS latency and stores data in + the Read FIFO. Note: The corresponding bit in the + FMC_SDCR2 register is read only. + 12 + 1 + + + RPIPE + Read pipe These bits define the delay, + in KCK_FMC clock cycles, for reading data after CAS + latency. Note: The corresponding bits in the + FMC_SDCR2 register is read only. + 13 + 2 + + + + + SDTR1 + SDTR1 + This register contains the timing parameters + of each SDRAM bank + 0x148 + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to Active These bits + define the delay between a Load Mode Register command + and an Active or Refresh command in number of memory + clock cycles. .... + 0 + 4 + + + TXSR + Exit Self-refresh delay These bits + define the delay from releasing the Self-refresh + command to issuing the Activate command in number of + memory clock cycles. .... Note: If two SDRAM devices + are used, the FMC_SDTR1 and FMC_SDTR2 must be + programmed with the same TXSR timing corresponding to + the slowest SDRAM device. + 4 + 4 + + + TRAS + Self refresh time These bits define the + minimum Self-refresh period in number of memory clock + cycles. .... + 8 + 4 + + + TRC + Row cycle delay These bits define the + delay between the Refresh command and the Activate + command, as well as the delay between two consecutive + Refresh commands. It is expressed in number of memory + clock cycles. The TRC timing is only configured in + the FMC_SDTR1 register. If two SDRAM devices are + used, the TRC must be programmed with the timings of + the slowest device. .... Note: TRC must match the TRC + and TRFC (Auto Refresh period) timings defined in the + SDRAM device datasheet. Note: The corresponding bits + in the FMC_SDTR2 register are dont + care. + 12 + 4 + + + TWR + Recovery delay These bits define the + delay between a Write and a Precharge command in + number of memory clock cycles. .... Note: TWR must be + programmed to match the write recovery time (tWR) + defined in the SDRAM datasheet, and to guarantee + that: TWR &#8805; TRAS - TRCD and TWR + &#8805;TRC - TRCD - TRP Example: TRAS= 4 cycles, + TRCD= 2 cycles. So, TWR &gt;= 2 cycles. TWR must + be programmed to 0x1. If two SDRAM devices are used, + the FMC_SDTR1 and FMC_SDTR2 must be programmed with + the same TWR timing corresponding to the slowest + SDRAM device. + 16 + 4 + + + TRP + Row precharge delay These bits define + the delay between a Precharge command and another + command in number of memory clock cycles. The TRP + timing is only configured in the FMC_SDTR1 register. + If two SDRAM devices are used, the TRP must be + programmed with the timing of the slowest device. + .... Note: The corresponding bits in the FMC_SDTR2 + register are dont care. + 20 + 4 + + + TRCD + Row to column delay These bits define + the delay between the Activate command and a + Read/Write command in number of memory clock cycles. + .... + 24 + 4 + + + + + SDTR2 + SDTR2 + This register contains the timing parameters + of each SDRAM bank + 0x14C + 0x20 + read-write + 0x0FFFFFFF + + + TMRD + Load Mode Register to Active These bits + define the delay between a Load Mode Register command + and an Active or Refresh command in number of memory + clock cycles. .... + 0 + 4 + + + TXSR + Exit Self-refresh delay These bits + define the delay from releasing the Self-refresh + command to issuing the Activate command in number of + memory clock cycles. .... Note: If two SDRAM devices + are used, the FMC_SDTR1 and FMC_SDTR2 must be + programmed with the same TXSR timing corresponding to + the slowest SDRAM device. + 4 + 4 + + + TRAS + Self refresh time These bits define the + minimum Self-refresh period in number of memory clock + cycles. .... + 8 + 4 + + + TRC + Row cycle delay These bits define the + delay between the Refresh command and the Activate + command, as well as the delay between two consecutive + Refresh commands. It is expressed in number of memory + clock cycles. The TRC timing is only configured in + the FMC_SDTR1 register. If two SDRAM devices are + used, the TRC must be programmed with the timings of + the slowest device. .... Note: TRC must match the TRC + and TRFC (Auto Refresh period) timings defined in the + SDRAM device datasheet. Note: The corresponding bits + in the FMC_SDTR2 register are dont + care. + 12 + 4 + + + TWR + Recovery delay These bits define the + delay between a Write and a Precharge command in + number of memory clock cycles. .... Note: TWR must be + programmed to match the write recovery time (tWR) + defined in the SDRAM datasheet, and to guarantee + that: TWR &#8805; TRAS - TRCD and TWR + &#8805;TRC - TRCD - TRP Example: TRAS= 4 cycles, + TRCD= 2 cycles. So, TWR &gt;= 2 cycles. TWR must + be programmed to 0x1. If two SDRAM devices are used, + the FMC_SDTR1 and FMC_SDTR2 must be programmed with + the same TWR timing corresponding to the slowest + SDRAM device. + 16 + 4 + + + TRP + Row precharge delay These bits define + the delay between a Precharge command and another + command in number of memory clock cycles. The TRP + timing is only configured in the FMC_SDTR1 register. + If two SDRAM devices are used, the TRP must be + programmed with the timing of the slowest device. + .... Note: The corresponding bits in the FMC_SDTR2 + register are dont care. + 20 + 4 + + + TRCD + Row to column delay These bits define + the delay between the Activate command and a + Read/Write command in number of memory clock cycles. + .... + 24 + 4 + + + + + SDCMR + SDCMR + This register contains the command issued + when the SDRAM device is accessed. This register is used + to initialize the SDRAM device, and to activate the + Self-refresh and the Power-down modes. As soon as the + MODE field is written, the command will be issued only to + one or to both SDRAM banks according to CTB1 and CTB2 + command bits. This register is the same for both SDRAM + banks. + 0x150 + 0x20 + read-write + 0x00000000 + + + MODE + Command mode These bits define the + command issued to the SDRAM device. Note: When a + command is issued, at least one Command Target Bank + bit ( CTB1 or CTB2) must be set otherwise the command + will be ignored. Note: If two SDRAM banks are used, + the Auto-refresh and PALL command must be issued + simultaneously to the two devices with CTB1 and CTB2 + bits set otherwise the command will be ignored. Note: + If only one SDRAM bank is used and a command is + issued with its associated CTB bit set, the other CTB + bit of the unused bank must be kept to + 0. + 0 + 3 + + + CTB2 + Command Target Bank 2 This bit indicates + whether the command will be issued to SDRAM Bank 2 or + not. + 3 + 1 + + + CTB1 + Command Target Bank 1 This bit indicates + whether the command will be issued to SDRAM Bank 1 or + not. + 4 + 1 + + + NRFS + Number of Auto-refresh These bits define + the number of consecutive Auto-refresh commands + issued when MODE = 011. .... + 5 + 4 + + + MRD + Mode Register definition This 14-bit + field defines the SDRAM Mode Register content. The + Mode Register is programmed using the Load Mode + Register command. The MRD[13:0] bits are also used to + program the extended mode register for mobile + SDRAM. + 9 + 14 + + + + + SDRTR + SDRTR + This register sets the refresh rate in + number of SDCLK clock cycles between the refresh cycles + by configuring the Refresh Timer Count value.Examplewhere + 64 ms is the SDRAM refresh period.The refresh rate must + be increased by 20 SDRAM clock cycles (as in the above + example) to obtain a safe margin if an internal refresh + request occurs when a read request has been accepted. It + corresponds to a COUNT value of 0000111000000 (448). This + 13-bit field is loaded into a timer which is decremented + using the SDRAM clock. This timer generates a refresh + pulse when zero is reached. The COUNT value must be set + at least to 41 SDRAM clock cycles.As soon as the + FMC_SDRTR register is programmed, the timer starts + counting. If the value programmed in the register is 0, + no refresh is carried out. This register must not be + reprogrammed after the initialization procedure to avoid + modifying the refresh rate.Each time a refresh pulse is + generated, this 13-bit COUNT field is reloaded into the + counter.If a memory access is in progress, the + Auto-refresh request is delayed. However, if the memory + access and Auto-refresh requests are generated + simultaneously, the Auto-refresh takes precedence. If the + memory access occurs during a refresh operation, the + request is buffered to be processed when the refresh is + complete.This register is common to SDRAM bank 1 and bank + 2. + 0x154 + 0x20 + 0x00000000 + + + CRE + Clear Refresh error flag This bit is + used to clear the Refresh Error Flag (RE) in the + Status Register. + 0 + 1 + write-only + + + COUNT + Refresh Timer Count This 13-bit field + defines the refresh rate of the SDRAM device. It is + expressed in number of memory clock cycles. It must + be set at least to 41 SDRAM clock cycles (0x29). + Refresh rate = (COUNT + 1) x SDRAM frequency clock + COUNT = (SDRAM refresh period / Number of rows) - + 20 + 1 + 13 + read-write + + + REIE + RES Interrupt Enable + 14 + 1 + read-write + + + + + SDSR + SDSR + SDRAM Status register + 0x158 + 0x20 + read-only + 0x00000000 + + + RE + Refresh error flag An interrupt is + generated if REIE = 1 and RE = 1 + 0 + 1 + + + MODES1 + Status Mode for Bank 1 These bits define + the Status Mode of SDRAM Bank 1. + 1 + 2 + + + MODES2 + Status Mode for Bank 2 These bits define + the Status Mode of SDRAM Bank 2. + 3 + 2 + + + + + + + CEC + CEC + CEC + 0x40006C00 + + 0x0 + 0x400 + registers + + + CEC + HDMI-CEC global interrupt + 94 + + + + CR + CR + CEC control register + 0x0 + 0x20 + read-write + 0x00000000 + + + CECEN + CEC Enable The CECEN bit is set and + cleared by software. CECEN=1 starts message reception + and enables the TXSOM control. CECEN=0 disables the + CEC peripheral, clears all bits of CEC_CR register + and aborts any on-going reception or + transmission. + 0 + 1 + + + TXSOM + Tx Start Of Message TXSOM is set by + software to command transmission of the first byte of + a CEC message. If the CEC message consists of only + one byte, TXEOM must be set before of TXSOM. + Start-Bit is effectively started on the CEC line + after SFT is counted. If TXSOM is set while a message + reception is ongoing, transmission will start after + the end of reception. TXSOM is cleared by hardware + after the last byte of the message is sent with a + positive acknowledge (TXEND=1), in case of + transmission underrun (TXUDR=1), negative acknowledge + (TXACKE=1), and transmission error (TXERR=1). It is + also cleared by CECEN=0. It is not cleared and + transmission is automatically retried in case of + arbitration lost (ARBLST=1). TXSOM can be also used + as a status bit informing application whether any + transmission request is pending or under execution. + The application can abort a transmission request at + any time by clearing the CECEN bit. Note: TXSOM must + be set when CECEN=1 TXSOM must be set when + transmission data is available into TXDR HEADERs + first four bits containing own peripheral address are + taken from TXDR[7:4], not from CEC_CFGR.OAR which is + used only for reception + 1 + 1 + + + TXEOM + Tx End Of Message The TXEOM bit is set + by software to command transmission of the last byte + of a CEC message. TXEOM is cleared by hardware at the + same time and under the same conditions as for TXSOM. + Note: TXEOM must be set when CECEN=1 TXEOM must be + set before writing transmission data to TXDR If TXEOM + is set when TXSOM=0, transmitted message will consist + of 1 byte (HEADER) only (PING message) + 2 + 1 + + + + + CFGR + CFGR + This register is used to configure the + HDMI-CEC controller. It is mandatory to write CEC_CFGR + only when CECEN=0. + 0x4 + 0x20 + read-write + 0x00000000 + + + SFT + Signal Free Time SFT bits are set by + software. In the SFT=0x0 configuration the number of + nominal data bit periods waited before transmission + is ruled by hardware according to the transmission + history. In all the other configurations the SFT + number is determined by software. * 0x0 ** 2.5 + Data-Bit periods if CEC is the last bus initiator + with unsuccessful transmission (ARBLST=1, TXERR=1, + TXUDR=1 or TXACKE= 1) ** 4 Data-Bit periods if CEC is + the new bus initiator ** 6 Data-Bit periods if CEC is + the last bus initiator with successful transmission + (TXEOM=1) * 0x1: 0.5 nominal data bit periods * 0x2: + 1.5 nominal data bit periods * 0x3: 2.5 nominal data + bit periods * 0x4: 3.5 nominal data bit periods * + 0x5: 4.5 nominal data bit periods * 0x6: 5.5 nominal + data bit periods * 0x7: 6.5 nominal data bit + periods + 0 + 3 + + + RXTOL + Rx-Tolerance The RXTOL bit is set and + cleared by software. ** Start-Bit, +/- 200 s rise, + +/- 200 s fall. ** Data-Bit: +/- 200 s rise. +/- 350 + s fall. ** Start-Bit: +/- 400 s rise, +/- 400 s fall + ** Data-Bit: +/-300 s rise, +/- 500 s + fall + 3 + 1 + + + BRESTP + Rx-Stop on Bit Rising Error The BRESTP + bit is set and cleared by software. + 4 + 1 + + + BREGEN + Generate Error-Bit on Bit Rising Error + The BREGEN bit is set and cleared by software. Note: + If BRDNOGEN=0, an Error-bit is generated upon BRE + detection with BRESTP=1 in broadcast even if + BREGEN=0 + 5 + 1 + + + LBPEGEN + Generate Error-Bit on Long Bit Period + Error The LBPEGEN bit is set and cleared by software. + Note: If BRDNOGEN=0, an Error-bit is generated upon + LBPE detection in broadcast even if + LBPEGEN=0 + 6 + 1 + + + BRDNOGEN + Avoid Error-Bit Generation in Broadcast + The BRDNOGEN bit is set and cleared by + software. + 7 + 1 + + + SFTOPT + SFT Option Bit The SFTOPT bit is set and + cleared by software. + 8 + 1 + + + OAR + Own addresses configuration The OAR bits + are set by software to select which destination + logical addresses has to be considered in receive + mode. Each bit, when set, enables the CEC logical + address identified by the given bit position. At the + end of HEADER reception, the received destination + address is compared with the enabled addresses. In + case of matching address, the incoming message is + acknowledged and received. In case of non-matching + address, the incoming message is received only in + listen mode (LSTN=1), but without acknowledge sent. + Broadcast messages are always received. Example: OAR + = 0b000 0000 0010 0001 means that CEC acknowledges + addresses 0x0 and 0x5. Consequently, each message + directed to one of these addresses is + received. + 16 + 15 + + + LSTN + Listen mode LSTN bit is set and cleared + by software. + 31 + 1 + + + + + TXDR + TXDR + CEC Tx data register + 0x8 + 0x20 + write-only + 0x00000000 + + + TXD + Tx Data register. TXD is a write-only + register containing the data byte to be transmitted. + Note: TXD must be written when + TXSTART=1 + 0 + 8 + + + + + RXDR + RXDR + CEC Rx Data Register + 0xC + 0x20 + read-only + 0x00000000 + + + RXD + Rx Data register. RXD is read-only and + contains the last data byte which has been received + from the CEC line. + 0 + 8 + + + + + ISR + ISR + CEC Interrupt and Status + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + RXBR + Rx-Byte Received The RXBR bit is set by + hardware to inform application that a new byte has + been received from the CEC line and stored into the + RXD buffer. RXBR is cleared by software write at + 1. + 0 + 1 + + + RXEND + End Of Reception RXEND is set by + hardware to inform application that the last byte of + a CEC message is received from the CEC line and + stored into the RXD buffer. RXEND is set at the same + time of RXBR. RXEND is cleared by software write at + 1. + 1 + 1 + + + RXOVR + Rx-Overrun RXOVR is set by hardware if + RXBR is not yet cleared at the time a new byte is + received on the CEC line and stored into RXD. RXOVR + assertion stops message reception so that no + acknowledge is sent. In case of broadcast, a negative + acknowledge is sent. RXOVR is cleared by software + write at 1. + 2 + 1 + + + BRE + Rx-Bit Rising Error BRE is set by + hardware in case a Data-Bit waveform is detected with + Bit Rising Error. BRE is set either at the time the + misplaced rising edge occurs, or at the end of the + maximum BRE tolerance allowed by RXTOL, in case + rising edge is still longing. BRE stops message + reception if BRESTP=1. BRE generates an Error-Bit on + the CEC line if BREGEN=1. BRE is cleared by software + write at 1. + 3 + 1 + + + SBPE + Rx-Short Bit Period Error SBPE is set by + hardware in case a Data-Bit waveform is detected with + Short Bit Period Error. SBPE is set at the time the + anticipated falling edge occurs. SBPE generates an + Error-Bit on the CEC line. SBPE is cleared by + software write at 1. + 4 + 1 + + + LBPE + Rx-Long Bit Period Error LBPE is set by + hardware in case a Data-Bit waveform is detected with + Long Bit Period Error. LBPE is set at the end of the + maximum bit-extension tolerance allowed by RXTOL, in + case falling edge is still longing. LBPE always stops + reception of the CEC message. LBPE generates an + Error-Bit on the CEC line if LBPEGEN=1. In case of + broadcast, Error-Bit is generated even in case of + LBPEGEN=0. LBPE is cleared by software write at + 1. + 5 + 1 + + + RXACKE + Rx-Missing Acknowledge In receive mode, + RXACKE is set by hardware to inform application that + no acknowledge was seen on the CEC line. RXACKE + applies only for broadcast messages and in listen + mode also for not directly addressed messages + (destination address not enabled in OAR). RXACKE + aborts message reception. RXACKE is cleared by + software write at 1. + 6 + 1 + + + ARBLST + Arbitration Lost ARBLST is set by + hardware to inform application that CEC device is + switching to reception due to arbitration lost event + following the TXSOM command. ARBLST can be due either + to a contending CEC device starting earlier or + starting at the same time but with higher HEADER + priority. After ARBLST assertion TXSOM bit keeps + pending for next transmission attempt. ARBLST is + cleared by software write at 1. + 7 + 1 + + + TXBR + Tx-Byte Request TXBR is set by hardware + to inform application that the next transmission data + has to be written to TXDR. TXBR is set when the 4th + bit of currently transmitted byte is sent. + Application must write the next byte to TXDR within 6 + nominal data-bit periods before transmission underrun + error occurs (TXUDR). TXBR is cleared by software + write at 1. + 8 + 1 + + + TXEND + End of Transmission TXEND is set by + hardware to inform application that the last byte of + the CEC message has been successfully transmitted. + TXEND clears the TXSOM and TXEOM control bits. TXEND + is cleared by software write at 1. + 9 + 1 + + + TXUDR + Tx-Buffer Underrun In transmission mode, + TXUDR is set by hardware if application was not in + time to load TXDR before of next byte transmission. + TXUDR aborts message transmission and clears TXSOM + and TXEOM control bits. TXUDR is cleared by software + write at 1 + 10 + 1 + + + TXERR + Tx-Error In transmission mode, TXERR is + set by hardware if the CEC initiator detects low + impedance on the CEC line while it is released. TXERR + aborts message transmission and clears TXSOM and + TXEOM controls. TXERR is cleared by software write at + 1. + 11 + 1 + + + TXACKE + Tx-Missing Acknowledge Error In + transmission mode, TXACKE is set by hardware to + inform application that no acknowledge was received. + In case of broadcast transmission, TXACKE informs + application that a negative acknowledge was received. + TXACKE aborts message transmission and clears TXSOM + and TXEOM controls. TXACKE is cleared by software + write at 1. + 12 + 1 + + + + + IER + IER + CEC interrupt enable register + 0x14 + 0x20 + read-write + 0x00000000 + + + RXBRIE + Rx-Byte Received Interrupt Enable The + RXBRIE bit is set and cleared by + software. + 0 + 1 + + + RXENDIE + End Of Reception Interrupt Enable The + RXENDIE bit is set and cleared by + software. + 1 + 1 + + + RXOVRIE + Rx-Buffer Overrun Interrupt Enable The + RXOVRIE bit is set and cleared by + software. + 2 + 1 + + + BREIE + Bit Rising Error Interrupt Enable The + BREIE bit is set and cleared by + software. + 3 + 1 + + + SBPEIE + Short Bit Period Error Interrupt Enable + The SBPEIE bit is set and cleared by + software. + 4 + 1 + + + LBPEIE + Long Bit Period Error Interrupt Enable + The LBPEIE bit is set and cleared by + software. + 5 + 1 + + + RXACKIE + Rx-Missing Acknowledge Error Interrupt + Enable The RXACKIE bit is set and cleared by + software. + 6 + 1 + + + ARBLSTIE + Arbitration Lost Interrupt Enable The + ARBLSTIE bit is set and cleared by + software. + 7 + 1 + + + TXBRIE + Tx-Byte Request Interrupt Enable The + TXBRIE bit is set and cleared by + software. + 8 + 1 + + + TXENDIE + Tx-End Of Message Interrupt Enable The + TXENDIE bit is set and cleared by + software. + 9 + 1 + + + TXUDRIE + Tx-Underrun Interrupt Enable The TXUDRIE + bit is set and cleared by software. + 10 + 1 + + + TXERRIE + Tx-Error Interrupt Enable The TXERRIE + bit is set and cleared by software. + 11 + 1 + + + TXACKIE + Tx-Missing Acknowledge Error Interrupt + Enable The TXACKEIE bit is set and cleared by + software. + 12 + 1 + + + + + + + HSEM + HSEM + HSEM + 0x58026400 + + 0x0 + 0x400 + registers + + + HSEM0 + HSEM global interrupt 1 + 125 + + + + HSEM_R0 + HSEM_R0 + HSEM register HSEM_R0 HSEM_R31 + 0x0 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R1 + HSEM_R1 + HSEM register HSEM_R0 HSEM_R31 + 0x4 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R2 + HSEM_R2 + HSEM register HSEM_R0 HSEM_R31 + 0x8 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R3 + HSEM_R3 + HSEM register HSEM_R0 HSEM_R31 + 0xC + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R4 + HSEM_R4 + HSEM register HSEM_R0 HSEM_R31 + 0x10 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R5 + HSEM_R5 + HSEM register HSEM_R0 HSEM_R31 + 0x14 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R6 + HSEM_R6 + HSEM register HSEM_R0 HSEM_R31 + 0x18 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R7 + HSEM_R7 + HSEM register HSEM_R0 HSEM_R31 + 0x1C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R8 + HSEM_R8 + HSEM register HSEM_R0 HSEM_R31 + 0x20 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R9 + HSEM_R9 + HSEM register HSEM_R0 HSEM_R31 + 0x24 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R10 + HSEM_R10 + HSEM register HSEM_R0 HSEM_R31 + 0x28 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R11 + HSEM_R11 + HSEM register HSEM_R0 HSEM_R31 + 0x2C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R12 + HSEM_R12 + HSEM register HSEM_R0 HSEM_R31 + 0x30 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R13 + HSEM_R13 + HSEM register HSEM_R0 HSEM_R31 + 0x34 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R14 + HSEM_R14 + HSEM register HSEM_R0 HSEM_R31 + 0x38 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R15 + HSEM_R15 + HSEM register HSEM_R0 HSEM_R31 + 0x3C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R16 + HSEM_R16 + HSEM register HSEM_R0 HSEM_R31 + 0x40 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R17 + HSEM_R17 + HSEM register HSEM_R0 HSEM_R31 + 0x44 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R18 + HSEM_R18 + HSEM register HSEM_R0 HSEM_R31 + 0x48 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R19 + HSEM_R19 + HSEM register HSEM_R0 HSEM_R31 + 0x4C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R20 + HSEM_R20 + HSEM register HSEM_R0 HSEM_R31 + 0x50 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R21 + HSEM_R21 + HSEM register HSEM_R0 HSEM_R31 + 0x54 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R22 + HSEM_R22 + HSEM register HSEM_R0 HSEM_R31 + 0x58 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R23 + HSEM_R23 + HSEM register HSEM_R0 HSEM_R31 + 0x5C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R24 + HSEM_R24 + HSEM register HSEM_R0 HSEM_R31 + 0x60 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R25 + HSEM_R25 + HSEM register HSEM_R0 HSEM_R31 + 0x64 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R26 + HSEM_R26 + HSEM register HSEM_R0 HSEM_R31 + 0x68 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R27 + HSEM_R27 + HSEM register HSEM_R0 HSEM_R31 + 0x6C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R28 + HSEM_R28 + HSEM register HSEM_R0 HSEM_R31 + 0x70 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R29 + HSEM_R29 + HSEM register HSEM_R0 HSEM_R31 + 0x74 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R30 + HSEM_R30 + HSEM register HSEM_R0 HSEM_R31 + 0x78 + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_R31 + HSEM_R31 + HSEM register HSEM_R0 HSEM_R31 + 0x7C + 0x20 + read-write + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR0 + HSEM_RLR0 + HSEM Read lock register + 0x80 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR1 + HSEM_RLR1 + HSEM Read lock register + 0x84 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR2 + HSEM_RLR2 + HSEM Read lock register + 0x88 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR3 + HSEM_RLR3 + HSEM Read lock register + 0x8C + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR4 + HSEM_RLR4 + HSEM Read lock register + 0x90 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR5 + HSEM_RLR5 + HSEM Read lock register + 0x94 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR6 + HSEM_RLR6 + HSEM Read lock register + 0x98 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR7 + HSEM_RLR7 + HSEM Read lock register + 0x9C + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR8 + HSEM_RLR8 + HSEM Read lock register + 0xA0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR9 + HSEM_RLR9 + HSEM Read lock register + 0xA4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR10 + HSEM_RLR10 + HSEM Read lock register + 0xA8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR11 + HSEM_RLR11 + HSEM Read lock register + 0xAC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR12 + HSEM_RLR12 + HSEM Read lock register + 0xB0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR13 + HSEM_RLR13 + HSEM Read lock register + 0xB4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR14 + HSEM_RLR14 + HSEM Read lock register + 0xB8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR15 + HSEM_RLR15 + HSEM Read lock register + 0xBC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR16 + HSEM_RLR16 + HSEM Read lock register + 0xC0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR17 + HSEM_RLR17 + HSEM Read lock register + 0xC4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR18 + HSEM_RLR18 + HSEM Read lock register + 0xC8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR19 + HSEM_RLR19 + HSEM Read lock register + 0xCC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR20 + HSEM_RLR20 + HSEM Read lock register + 0xD0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR21 + HSEM_RLR21 + HSEM Read lock register + 0xD4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR22 + HSEM_RLR22 + HSEM Read lock register + 0xD8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR23 + HSEM_RLR23 + HSEM Read lock register + 0xDC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR24 + HSEM_RLR24 + HSEM Read lock register + 0xE0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR25 + HSEM_RLR25 + HSEM Read lock register + 0xE4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR26 + HSEM_RLR26 + HSEM Read lock register + 0xE8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR27 + HSEM_RLR27 + HSEM Read lock register + 0xEC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR28 + HSEM_RLR28 + HSEM Read lock register + 0xF0 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR29 + HSEM_RLR29 + HSEM Read lock register + 0xF4 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR30 + HSEM_RLR30 + HSEM Read lock register + 0xF8 + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_RLR31 + HSEM_RLR31 + HSEM Read lock register + 0xFC + 0x20 + read-only + 0x00000000 + + + PROCID + Semaphore ProcessID + 0 + 8 + + + MASTERID + Semaphore MasterID + 8 + 8 + + + LOCK + Lock indication + 31 + 1 + + + + + HSEM_IER + HSEM_IER + HSEM Interrupt enable register + 0x100 + 0x20 + read-write + 0x00000000 + + + ISEM0 + Interrupt semaphore n enable + bit + 0 + 1 + + + ISEM1 + Interrupt semaphore n enable + bit + 1 + 1 + + + ISEM2 + Interrupt semaphore n enable + bit + 2 + 1 + + + ISEM3 + Interrupt semaphore n enable + bit + 3 + 1 + + + ISEM4 + Interrupt semaphore n enable + bit + 4 + 1 + + + ISEM5 + Interrupt semaphore n enable + bit + 5 + 1 + + + ISEM6 + Interrupt semaphore n enable + bit + 6 + 1 + + + ISEM7 + Interrupt semaphore n enable + bit + 7 + 1 + + + ISEM8 + Interrupt semaphore n enable + bit + 8 + 1 + + + ISEM9 + Interrupt semaphore n enable + bit + 9 + 1 + + + ISEM10 + Interrupt semaphore n enable + bit + 10 + 1 + + + ISEM11 + Interrupt semaphore n enable + bit + 11 + 1 + + + ISEM12 + Interrupt semaphore n enable + bit + 12 + 1 + + + ISEM13 + Interrupt semaphore n enable + bit + 13 + 1 + + + ISEM14 + Interrupt semaphore n enable + bit + 14 + 1 + + + ISEM15 + Interrupt semaphore n enable + bit + 15 + 1 + + + ISEM16 + Interrupt semaphore n enable + bit + 16 + 1 + + + ISEM17 + Interrupt semaphore n enable + bit + 17 + 1 + + + ISEM18 + Interrupt semaphore n enable + bit + 18 + 1 + + + ISEM19 + Interrupt semaphore n enable + bit + 19 + 1 + + + ISEM20 + Interrupt semaphore n enable + bit + 20 + 1 + + + ISEM21 + Interrupt semaphore n enable + bit + 21 + 1 + + + ISEM22 + Interrupt semaphore n enable + bit + 22 + 1 + + + ISEM23 + Interrupt semaphore n enable + bit + 23 + 1 + + + ISEM24 + Interrupt semaphore n enable + bit + 24 + 1 + + + ISEM25 + Interrupt semaphore n enable + bit + 25 + 1 + + + ISEM26 + Interrupt semaphore n enable + bit + 26 + 1 + + + ISEM27 + Interrupt semaphore n enable + bit + 27 + 1 + + + ISEM28 + Interrupt semaphore n enable + bit + 28 + 1 + + + ISEM29 + Interrupt semaphore n enable + bit + 29 + 1 + + + ISEM30 + Interrupt semaphore n enable + bit + 30 + 1 + + + ISEM31 + Interrupt(N) semaphore n enable + bit. + 31 + 1 + + + + + HSEM_ICR + HSEM_ICR + HSEM Interrupt clear register + 0x104 + 0x20 + read-only + 0x00000000 + + + ISEM0 + Interrupt(N) semaphore n clear + bit + 0 + 1 + + + ISEM1 + Interrupt(N) semaphore n clear + bit + 1 + 1 + + + ISEM2 + Interrupt(N) semaphore n clear + bit + 2 + 1 + + + ISEM3 + Interrupt(N) semaphore n clear + bit + 3 + 1 + + + ISEM4 + Interrupt(N) semaphore n clear + bit + 4 + 1 + + + ISEM5 + Interrupt(N) semaphore n clear + bit + 5 + 1 + + + ISEM6 + Interrupt(N) semaphore n clear + bit + 6 + 1 + + + ISEM7 + Interrupt(N) semaphore n clear + bit + 7 + 1 + + + ISEM8 + Interrupt(N) semaphore n clear + bit + 8 + 1 + + + ISEM9 + Interrupt(N) semaphore n clear + bit + 9 + 1 + + + ISEM10 + Interrupt(N) semaphore n clear + bit + 10 + 1 + + + ISEM11 + Interrupt(N) semaphore n clear + bit + 11 + 1 + + + ISEM12 + Interrupt(N) semaphore n clear + bit + 12 + 1 + + + ISEM13 + Interrupt(N) semaphore n clear + bit + 13 + 1 + + + ISEM14 + Interrupt(N) semaphore n clear + bit + 14 + 1 + + + ISEM15 + Interrupt(N) semaphore n clear + bit + 15 + 1 + + + ISEM16 + Interrupt(N) semaphore n clear + bit + 16 + 1 + + + ISEM17 + Interrupt(N) semaphore n clear + bit + 17 + 1 + + + ISEM18 + Interrupt(N) semaphore n clear + bit + 18 + 1 + + + ISEM19 + Interrupt(N) semaphore n clear + bit + 19 + 1 + + + ISEM20 + Interrupt(N) semaphore n clear + bit + 20 + 1 + + + ISEM21 + Interrupt(N) semaphore n clear + bit + 21 + 1 + + + ISEM22 + Interrupt(N) semaphore n clear + bit + 22 + 1 + + + ISEM23 + Interrupt(N) semaphore n clear + bit + 23 + 1 + + + ISEM24 + Interrupt(N) semaphore n clear + bit + 24 + 1 + + + ISEM25 + Interrupt(N) semaphore n clear + bit + 25 + 1 + + + ISEM26 + Interrupt(N) semaphore n clear + bit + 26 + 1 + + + ISEM27 + Interrupt(N) semaphore n clear + bit + 27 + 1 + + + ISEM28 + Interrupt(N) semaphore n clear + bit + 28 + 1 + + + ISEM29 + Interrupt(N) semaphore n clear + bit + 29 + 1 + + + ISEM30 + Interrupt(N) semaphore n clear + bit + 30 + 1 + + + ISEM31 + Interrupt(N) semaphore n clear + bit + 31 + 1 + + + + + HSEM_ISR + HSEM_ISR + HSEM Interrupt status register + 0x108 + 0x20 + read-only + 0x00000000 + + + ISEM0 + Interrupt(N) semaphore n status bit + before enable (mask) + 0 + 1 + + + ISEM1 + Interrupt(N) semaphore n status bit + before enable (mask) + 1 + 1 + + + ISEM2 + Interrupt(N) semaphore n status bit + before enable (mask) + 2 + 1 + + + ISEM3 + Interrupt(N) semaphore n status bit + before enable (mask) + 3 + 1 + + + ISEM4 + Interrupt(N) semaphore n status bit + before enable (mask) + 4 + 1 + + + ISEM5 + Interrupt(N) semaphore n status bit + before enable (mask) + 5 + 1 + + + ISEM6 + Interrupt(N) semaphore n status bit + before enable (mask) + 6 + 1 + + + ISEM7 + Interrupt(N) semaphore n status bit + before enable (mask) + 7 + 1 + + + ISEM8 + Interrupt(N) semaphore n status bit + before enable (mask) + 8 + 1 + + + ISEM9 + Interrupt(N) semaphore n status bit + before enable (mask) + 9 + 1 + + + ISEM10 + Interrupt(N) semaphore n status bit + before enable (mask) + 10 + 1 + + + ISEM11 + Interrupt(N) semaphore n status bit + before enable (mask) + 11 + 1 + + + ISEM12 + Interrupt(N) semaphore n status bit + before enable (mask) + 12 + 1 + + + ISEM13 + Interrupt(N) semaphore n status bit + before enable (mask) + 13 + 1 + + + ISEM14 + Interrupt(N) semaphore n status bit + before enable (mask) + 14 + 1 + + + ISEM15 + Interrupt(N) semaphore n status bit + before enable (mask) + 15 + 1 + + + ISEM16 + Interrupt(N) semaphore n status bit + before enable (mask) + 16 + 1 + + + ISEM17 + Interrupt(N) semaphore n status bit + before enable (mask) + 17 + 1 + + + ISEM18 + Interrupt(N) semaphore n status bit + before enable (mask) + 18 + 1 + + + ISEM19 + Interrupt(N) semaphore n status bit + before enable (mask) + 19 + 1 + + + ISEM20 + Interrupt(N) semaphore n status bit + before enable (mask) + 20 + 1 + + + ISEM21 + Interrupt(N) semaphore n status bit + before enable (mask) + 21 + 1 + + + ISEM22 + Interrupt(N) semaphore n status bit + before enable (mask) + 22 + 1 + + + ISEM23 + Interrupt(N) semaphore n status bit + before enable (mask) + 23 + 1 + + + ISEM24 + Interrupt(N) semaphore n status bit + before enable (mask) + 24 + 1 + + + ISEM25 + Interrupt(N) semaphore n status bit + before enable (mask) + 25 + 1 + + + ISEM26 + Interrupt(N) semaphore n status bit + before enable (mask) + 26 + 1 + + + ISEM27 + Interrupt(N) semaphore n status bit + before enable (mask) + 27 + 1 + + + ISEM28 + Interrupt(N) semaphore n status bit + before enable (mask) + 28 + 1 + + + ISEM29 + Interrupt(N) semaphore n status bit + before enable (mask) + 29 + 1 + + + ISEM30 + Interrupt(N) semaphore n status bit + before enable (mask) + 30 + 1 + + + ISEM31 + Interrupt(N) semaphore n status bit + before enable (mask) + 31 + 1 + + + + + HSEM_MISR + HSEM_MISR + HSEM Masked interrupt status + register + 0x10C + 0x20 + read-only + 0x00000000 + + + ISEM0 + masked interrupt(N) semaphore n status + bit after enable (mask) + 0 + 1 + + + ISEM1 + masked interrupt(N) semaphore n status + bit after enable (mask) + 1 + 1 + + + ISEM2 + masked interrupt(N) semaphore n status + bit after enable (mask) + 2 + 1 + + + ISEM3 + masked interrupt(N) semaphore n status + bit after enable (mask) + 3 + 1 + + + ISEM4 + masked interrupt(N) semaphore n status + bit after enable (mask) + 4 + 1 + + + ISEM5 + masked interrupt(N) semaphore n status + bit after enable (mask) + 5 + 1 + + + ISEM6 + masked interrupt(N) semaphore n status + bit after enable (mask) + 6 + 1 + + + ISEM7 + masked interrupt(N) semaphore n status + bit after enable (mask) + 7 + 1 + + + ISEM8 + masked interrupt(N) semaphore n status + bit after enable (mask) + 8 + 1 + + + ISEM9 + masked interrupt(N) semaphore n status + bit after enable (mask) + 9 + 1 + + + ISEM10 + masked interrupt(N) semaphore n status + bit after enable (mask) + 10 + 1 + + + ISEM11 + masked interrupt(N) semaphore n status + bit after enable (mask) + 11 + 1 + + + ISEM12 + masked interrupt(N) semaphore n status + bit after enable (mask) + 12 + 1 + + + ISEM13 + masked interrupt(N) semaphore n status + bit after enable (mask) + 13 + 1 + + + ISEM14 + masked interrupt(N) semaphore n status + bit after enable (mask) + 14 + 1 + + + ISEM15 + masked interrupt(N) semaphore n status + bit after enable (mask) + 15 + 1 + + + ISEM16 + masked interrupt(N) semaphore n status + bit after enable (mask) + 16 + 1 + + + ISEM17 + masked interrupt(N) semaphore n status + bit after enable (mask) + 17 + 1 + + + ISEM18 + masked interrupt(N) semaphore n status + bit after enable (mask) + 18 + 1 + + + ISEM19 + masked interrupt(N) semaphore n status + bit after enable (mask) + 19 + 1 + + + ISEM20 + masked interrupt(N) semaphore n status + bit after enable (mask) + 20 + 1 + + + ISEM21 + masked interrupt(N) semaphore n status + bit after enable (mask) + 21 + 1 + + + ISEM22 + masked interrupt(N) semaphore n status + bit after enable (mask) + 22 + 1 + + + ISEM23 + masked interrupt(N) semaphore n status + bit after enable (mask) + 23 + 1 + + + ISEM24 + masked interrupt(N) semaphore n status + bit after enable (mask) + 24 + 1 + + + ISEM25 + masked interrupt(N) semaphore n status + bit after enable (mask) + 25 + 1 + + + ISEM26 + masked interrupt(N) semaphore n status + bit after enable (mask) + 26 + 1 + + + ISEM27 + masked interrupt(N) semaphore n status + bit after enable (mask) + 27 + 1 + + + ISEM28 + masked interrupt(N) semaphore n status + bit after enable (mask) + 28 + 1 + + + ISEM29 + masked interrupt(N) semaphore n status + bit after enable (mask) + 29 + 1 + + + ISEM30 + masked interrupt(N) semaphore n status + bit after enable (mask) + 30 + 1 + + + ISEM31 + masked interrupt(N) semaphore n status + bit after enable (mask) + 31 + 1 + + + + + HSEM_CR + HSEM_CR + HSEM Clear register + 0x140 + 0x20 + read-write + 0x00000000 + + + MASTERID + MasterID of semaphores to be + cleared + 8 + 8 + + + KEY + Semaphore clear Key + 16 + 16 + + + + + HSEM_KEYR + HSEM_KEYR + HSEM Interrupt clear register + 0x144 + 0x20 + read-write + 0x00000000 + + + KEY + Semaphore Clear Key + 16 + 16 + + + + + + + I2C1 + I2C + I2C + 0x40005400 + + 0x0 + 0x400 + registers + + + I2C1_EV + I2C1 event interrupt + 31 + + + I2C1_ER + I2C1 error interrupt + 32 + + + + CR1 + CR1 + Access: No wait states, except if a write + access occurs while a write access to this register is + ongoing. In this case, wait states are inserted in the + second write access until the previous one is completed. + The latency of the second write access can be up to 2 x + PCLK1 + 6 x I2CCLK. + 0x0 + 0x20 + read-write + 0x00000000 + + + PE + Peripheral enable Note: When PE=0, the + I2C SCL and SDA lines are released. Internal state + machines and status bits are put back to their reset + value. When cleared, PE must be kept low for at least + 3 APB clock cycles. + 0 + 1 + + + TXIE + TX Interrupt enable + 1 + 1 + + + RXIE + RX Interrupt enable + 2 + 1 + + + ADDRIE + Address match Interrupt enable (slave + only) + 3 + 1 + + + NACKIE + Not acknowledge received Interrupt + enable + 4 + 1 + + + STOPIE + STOP detection Interrupt + enable + 5 + 1 + + + TCIE + Transfer Complete interrupt enable Note: + Any of these events will generate an interrupt: + Transfer Complete (TC) Transfer Complete Reload + (TCR) + 6 + 1 + + + ERRIE + Error interrupts enable Note: Any of + these errors generate an interrupt: Arbitration Loss + (ARLO) Bus Error detection (BERR) Overrun/Underrun + (OVR) Timeout detection (TIMEOUT) PEC error detection + (PECERR) Alert pin event detection + (ALERT) + 7 + 1 + + + DNF + Digital noise filter These bits are used + to configure the digital noise filter on SDA and SCL + input. The digital filter will filter spikes with a + length of up to DNF[3:0] * tI2CCLK ... Note: If the + analog filter is also enabled, the digital filter is + added to the analog filter. This filter can only be + programmed when the I2C is disabled (PE = + 0). + 8 + 4 + + + ANFOFF + Analog noise filter OFF Note: This bit + can only be programmed when the I2C is disabled (PE = + 0). + 12 + 1 + + + TXDMAEN + DMA transmission requests + enable + 14 + 1 + + + RXDMAEN + DMA reception requests + enable + 15 + 1 + + + SBC + Slave byte control This bit is used to + enable hardware byte control in slave + mode. + 16 + 1 + + + NOSTRETCH + Clock stretching disable This bit is + used to disable clock stretching in slave mode. It + must be kept cleared in master mode. Note: This bit + can only be programmed when the I2C is disabled (PE = + 0). + 17 + 1 + + + WUPEN + Wakeup from Stop mode enable Note: If + the Wakeup from Stop mode feature is not supported, + this bit is reserved and forced by hardware to 0. + Please refer to Section25.3: I2C implementation. + Note: WUPEN can be set only when DNF = + 0000 + 18 + 1 + + + GCEN + General call enable + 19 + 1 + + + SMBHEN + SMBus Host address enable Note: If the + SMBus feature is not supported, this bit is reserved + and forced by hardware to 0. Please refer to + Section25.3: I2C implementation. + 20 + 1 + + + SMBDEN + SMBus Device Default address enable + Note: If the SMBus feature is not supported, this bit + is reserved and forced by hardware to 0. Please refer + to Section25.3: I2C implementation. + 21 + 1 + + + ALERTEN + SMBus alert enable Device mode + (SMBHEN=0): Host mode (SMBHEN=1): Note: When + ALERTEN=0, the SMBA pin can be used as a standard + GPIO. If the SMBus feature is not supported, this bit + is reserved and forced by hardware to 0. Please refer + to Section25.3: I2C implementation. + 22 + 1 + + + PECEN + PEC enable Note: If the SMBus feature is + not supported, this bit is reserved and forced by + hardware to 0. Please refer to Section25.3: I2C + implementation. + 23 + 1 + + + + + CR2 + CR2 + Access: No wait states, except if a write + access occurs while a write access to this register is + ongoing. In this case, wait states are inserted in the + second write access until the previous one is completed. + The latency of the second write access can be up to 2 x + PCLK1 + 6 x I2CCLK. + 0x4 + 0x20 + read-write + 0x00000000 + + + SADD0 + Slave address bit 0 (master mode) In + 7-bit addressing mode (ADD10 = 0): This bit is dont + care In 10-bit addressing mode (ADD10 = 1): This bit + should be written with bit 0 of the slave address to + be sent Note: Changing these bits when the START bit + is set is not allowed. + 0 + 1 + + + SADD1 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 1 + 1 + + + SADD2 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 2 + 1 + + + SADD3 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 3 + 1 + + + SADD4 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 4 + 1 + + + SADD5 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 5 + 1 + + + SADD6 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 6 + 1 + + + SADD7 + Slave address bit 7:1 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits should + be written with the 7-bit slave address to be sent In + 10-bit addressing mode (ADD10 = 1): These bits should + be written with bits 7:1 of the slave address to be + sent. Note: Changing these bits when the START bit is + set is not allowed. + 7 + 1 + + + SADD8 + Slave address bit 9:8 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits are + dont care In 10-bit addressing mode (ADD10 = 1): + These bits should be written with bits 9:8 of the + slave address to be sent Note: Changing these bits + when the START bit is set is not + allowed. + 8 + 1 + + + SADD9 + Slave address bit 9:8 (master mode) In + 7-bit addressing mode (ADD10 = 0): These bits are + dont care In 10-bit addressing mode (ADD10 = 1): + These bits should be written with bits 9:8 of the + slave address to be sent Note: Changing these bits + when the START bit is set is not + allowed. + 9 + 1 + + + RD_WRN + Transfer direction (master mode) Note: + Changing this bit when the START bit is set is not + allowed. + 10 + 1 + + + ADD10 + 10-bit addressing mode (master mode) + Note: Changing this bit when the START bit is set is + not allowed. + 11 + 1 + + + HEAD10R + 10-bit address header only read + direction (master receiver mode) Note: Changing this + bit when the START bit is set is not + allowed. + 12 + 1 + + + START + Start generation This bit is set by + software, and cleared by hardware after the Start + followed by the address sequence is sent, by an + arbitration loss, by a timeout error detection, or + when PE = 0. It can also be cleared by software by + writing 1 to the ADDRCF bit in the I2C_ICR register. + If the I2C is already in master mode with AUTOEND = + 0, setting this bit generates a Repeated Start + condition when RELOAD=0, after the end of the NBYTES + transfer. Otherwise setting this bit will generate a + START condition once the bus is free. Note: Writing 0 + to this bit has no effect. The START bit can be set + even if the bus is BUSY or I2C is in slave mode. This + bit has no effect when RELOAD is set. + 13 + 1 + + + STOP + Stop generation (master mode) The bit is + set by software, cleared by hardware when a Stop + condition is detected, or when PE = 0. In Master + Mode: Note: Writing 0 to this bit has no + effect. + 14 + 1 + + + NACK + NACK generation (slave mode) The bit is + set by software, cleared by hardware when the NACK is + sent, or when a STOP condition or an Address matched + is received, or when PE=0. Note: Writing 0 to this + bit has no effect. This bit is used in slave mode + only: in master receiver mode, NACK is automatically + generated after last byte preceding STOP or RESTART + condition, whatever the NACK bit value. When an + overrun occurs in slave receiver NOSTRETCH mode, a + NACK is automatically generated whatever the NACK bit + value. When hardware PEC checking is enabled + (PECBYTE=1), the PEC acknowledge value does not + depend on the NACK value. + 15 + 1 + + + NBYTES + Number of bytes The number of bytes to + be transmitted/received is programmed there. This + field is dont care in slave mode with SBC=0. Note: + Changing these bits when the START bit is set is not + allowed. + 16 + 8 + + + RELOAD + NBYTES reload mode This bit is set and + cleared by software. + 24 + 1 + + + AUTOEND + Automatic end mode (master mode) This + bit is set and cleared by software. Note: This bit + has no effect in slave mode or when the RELOAD bit is + set. + 25 + 1 + + + PECBYTE + Packet error checking byte This bit is + set by software, and cleared by hardware when the PEC + is transferred, or when a STOP condition or an + Address matched is received, also when PE=0. Note: + Writing 0 to this bit has no effect. This bit has no + effect when RELOAD is set. This bit has no effect is + slave mode when SBC=0. If the SMBus feature is not + supported, this bit is reserved and forced by + hardware to 0. Please refer to Section25.3: I2C + implementation. + 26 + 1 + + + + + OAR1 + OAR1 + Access: No wait states, except if a write + access occurs while a write access to this register is + ongoing. In this case, wait states are inserted in the + second write access until the previous one is completed. + The latency of the second write access can be up to 2 x + PCLK1 + 6 x I2CCLK. + 0x8 + 0x20 + read-write + 0x00000000 + + + OA1 + Interface address 7-bit addressing mode: + dont care 10-bit addressing mode: bits 9:8 of address + Note: These bits can be written only when OA1EN=0. + OA1[7:1]: Interface address Bits 7:1 of address Note: + These bits can be written only when OA1EN=0. OA1[0]: + Interface address 7-bit addressing mode: dont care + 10-bit addressing mode: bit 0 of address Note: This + bit can be written only when OA1EN=0. + 0 + 10 + + + OA1MODE + Own Address 1 10-bit mode Note: This bit + can be written only when OA1EN=0. + 10 + 1 + + + OA1EN + Own Address 1 enable + 15 + 1 + + + + + OAR2 + OAR2 + Access: No wait states, except if a write + access occurs while a write access to this register is + ongoing. In this case, wait states are inserted in the + second write access until the previous one is completed. + The latency of the second write access can be up to 2 x + PCLK1 + 6 x I2CCLK. + 0xC + 0x20 + read-write + 0x00000000 + + + OA2 + Interface address bits 7:1 of address + Note: These bits can be written only when + OA2EN=0. + 1 + 7 + + + OA2MSK + Own Address 2 masks Note: These bits can + be written only when OA2EN=0. As soon as OA2MSK is + not equal to 0, the reserved I2C addresses (0b0000xxx + and 0b1111xxx) are not acknowledged even if the + comparison matches. + 8 + 3 + + + OA2EN + Own Address 2 enable + 15 + 1 + + + + + TIMINGR + TIMINGR + Access: No wait states + 0x10 + 0x20 + read-write + 0x00000000 + + + SCLL + SCL low period (master mode) This field + is used to generate the SCL low period in master + mode. tSCLL = (SCLL+1) x tPRESC Note: SCLL is also + used to generate tBUF and tSU:STA + timings. + 0 + 8 + + + SCLH + SCL high period (master mode) This field + is used to generate the SCL high period in master + mode. tSCLH = (SCLH+1) x tPRESC Note: SCLH is also + used to generate tSU:STO and tHD:STA + timing. + 8 + 8 + + + SDADEL + Data hold time This field is used to + generate the delay tSDADEL between SCL falling edge + and SDA edge. In master mode and in slave mode with + NOSTRETCH = 0, the SCL line is stretched low during + tSDADEL. tSDADEL= SDADEL x tPRESC Note: SDADEL is + used to generate tHD:DAT timing. + 16 + 4 + + + SCLDEL + Data setup time This field is used to + generate a delay tSCLDEL between SDA edge and SCL + rising edge. In master mode and in slave mode with + NOSTRETCH = 0, the SCL line is stretched low during + tSCLDEL. tSCLDEL = (SCLDEL+1) x tPRESC Note: tSCLDEL + is used to generate tSU:DAT timing. + 20 + 4 + + + PRESC + Timing prescaler This field is used to + prescale I2CCLK in order to generate the clock period + tPRESC used for data setup and hold counters (refer + to I2C timings on page9) and for SCL high and low + level counters (refer to I2C master initialization on + page24). tPRESC = (PRESC+1) x tI2CCLK + 28 + 4 + + + + + TIMEOUTR + TIMEOUTR + Access: No wait states, except if a write + access occurs while a write access to this register is + ongoing. In this case, wait states are inserted in the + second write access until the previous one is completed. + The latency of the second write access can be up to 2 x + PCLK1 + 6 x I2CCLK. + 0x14 + 0x20 + read-write + 0x00000000 + + + TIMEOUTA + Bus Timeout A This field is used to + configure: The SCL low timeout condition tTIMEOUT + when TIDLE=0 tTIMEOUT= (TIMEOUTA+1) x 2048 x tI2CCLK + The bus idle condition (both SCL and SDA high) when + TIDLE=1 tIDLE= (TIMEOUTA+1) x 4 x tI2CCLK Note: These + bits can be written only when + TIMOUTEN=0. + 0 + 12 + + + TIDLE + Idle clock timeout detection Note: This + bit can be written only when + TIMOUTEN=0. + 12 + 1 + + + TIMOUTEN + Clock timeout enable + 15 + 1 + + + TIMEOUTB + Bus timeout B This field is used to + configure the cumulative clock extension timeout: In + master mode, the master cumulative clock low extend + time (tLOW:MEXT) is detected In slave mode, the slave + cumulative clock low extend time (tLOW:SEXT) is + detected tLOW:EXT= (TIMEOUTB+1) x 2048 x tI2CCLK + Note: These bits can be written only when + TEXTEN=0. + 16 + 12 + + + TEXTEN + Extended clock timeout + enable + 31 + 1 + + + + + ISR + ISR + Access: No wait states + 0x18 + 0x20 + 0x00000001 + + + TXE + Transmit data register empty + (transmitters) This bit is set by hardware when the + I2C_TXDR register is empty. It is cleared when the + next data to be sent is written in the I2C_TXDR + register. This bit can be written to 1 by software in + order to flush the transmit data register I2C_TXDR. + Note: This bit is set by hardware when + PE=0. + 0 + 1 + read-write + + + TXIS + Transmit interrupt status (transmitters) + This bit is set by hardware when the I2C_TXDR + register is empty and the data to be transmitted must + be written in the I2C_TXDR register. It is cleared + when the next data to be sent is written in the + I2C_TXDR register. This bit can be written to 1 by + software when NOSTRETCH=1 only, in order to generate + a TXIS event (interrupt if TXIE=1 or DMA request if + TXDMAEN=1). Note: This bit is cleared by hardware + when PE=0. + 1 + 1 + read-write + + + RXNE + Receive data register not empty + (receivers) This bit is set by hardware when the + received data is copied into the I2C_RXDR register, + and is ready to be read. It is cleared when I2C_RXDR + is read. Note: This bit is cleared by hardware when + PE=0. + 2 + 1 + read-only + + + ADDR + Address matched (slave mode) This bit is + set by hardware as soon as the received slave address + matched with one of the enabled slave addresses. It + is cleared by software by setting ADDRCF bit. Note: + This bit is cleared by hardware when + PE=0. + 3 + 1 + read-only + + + NACKF + Not Acknowledge received flag This flag + is set by hardware when a NACK is received after a + byte transmission. It is cleared by software by + setting the NACKCF bit. Note: This bit is cleared by + hardware when PE=0. + 4 + 1 + read-only + + + STOPF + Stop detection flag This flag is set by + hardware when a Stop condition is detected on the bus + and the peripheral is involved in this transfer: + either as a master, provided that the STOP condition + is generated by the peripheral. or as a slave, + provided that the peripheral has been addressed + previously during this transfer. It is cleared by + software by setting the STOPCF bit. Note: This bit is + cleared by hardware when PE=0. + 5 + 1 + read-only + + + TC + Transfer Complete (master mode) This + flag is set by hardware when RELOAD=0, AUTOEND=0 and + NBYTES data have been transferred. It is cleared by + software when START bit or STOP bit is set. Note: + This bit is cleared by hardware when + PE=0. + 6 + 1 + read-only + + + TCR + Transfer Complete Reload This flag is + set by hardware when RELOAD=1 and NBYTES data have + been transferred. It is cleared by software when + NBYTES is written to a non-zero value. Note: This bit + is cleared by hardware when PE=0. This flag is only + for master mode, or for slave mode when the SBC bit + is set. + 7 + 1 + read-only + + + BERR + Bus error This flag is set by hardware + when a misplaced Start or Stop condition is detected + whereas the peripheral is involved in the transfer. + The flag is not set during the address phase in slave + mode. It is cleared by software by setting BERRCF + bit. Note: This bit is cleared by hardware when + PE=0. + 8 + 1 + read-only + + + ARLO + Arbitration lost This flag is set by + hardware in case of arbitration loss. It is cleared + by software by setting the ARLOCF bit. Note: This bit + is cleared by hardware when PE=0. + 9 + 1 + read-only + + + OVR + Overrun/Underrun (slave mode) This flag + is set by hardware in slave mode with NOSTRETCH=1, + when an overrun/underrun error occurs. It is cleared + by software by setting the OVRCF bit. Note: This bit + is cleared by hardware when PE=0. + 10 + 1 + read-only + + + PECERR + PEC Error in reception This flag is set + by hardware when the received PEC does not match with + the PEC register content. A NACK is automatically + sent after the wrong PEC reception. It is cleared by + software by setting the PECCF bit. Note: This bit is + cleared by hardware when PE=0. If the SMBus feature + is not supported, this bit is reserved and forced by + hardware to 0. Please refer to Section25.3: I2C + implementation. + 11 + 1 + read-only + + + TIMEOUT + Timeout or tLOW detection flag This flag + is set by hardware when a timeout or extended clock + timeout occurred. It is cleared by software by + setting the TIMEOUTCF bit. Note: This bit is cleared + by hardware when PE=0. If the SMBus feature is not + supported, this bit is reserved and forced by + hardware to 0. Please refer to Section25.3: I2C + implementation. + 12 + 1 + read-only + + + ALERT + SMBus alert This flag is set by hardware + when SMBHEN=1 (SMBus host configuration), ALERTEN=1 + and a SMBALERT event (falling edge) is detected on + SMBA pin. It is cleared by software by setting the + ALERTCF bit. Note: This bit is cleared by hardware + when PE=0. If the SMBus feature is not supported, + this bit is reserved and forced by hardware to 0. + Please refer to Section25.3: I2C + implementation. + 13 + 1 + read-only + + + BUSY + Bus busy This flag indicates that a + communication is in progress on the bus. It is set by + hardware when a START condition is detected. It is + cleared by hardware when a Stop condition is + detected, or when PE=0. + 15 + 1 + read-only + + + DIR + Transfer direction (Slave mode) This + flag is updated when an address match event occurs + (ADDR=1). + 16 + 1 + read-only + + + ADDCODE + Address match code (Slave mode) These + bits are updated with the received address when an + address match event occurs (ADDR = 1). In the case of + a 10-bit address, ADDCODE provides the 10-bit header + followed by the 2 MSBs of the address. + 17 + 7 + read-only + + + + + ICR + ICR + Access: No wait states + 0x1C + 0x20 + write-only + 0x00000000 + + + ADDRCF + Address matched flag clear Writing 1 to + this bit clears the ADDR flag in the I2C_ISR + register. Writing 1 to this bit also clears the START + bit in the I2C_CR2 register. + 3 + 1 + + + NACKCF + Not Acknowledge flag clear Writing 1 to + this bit clears the ACKF flag in I2C_ISR + register. + 4 + 1 + + + STOPCF + Stop detection flag clear Writing 1 to + this bit clears the STOPF flag in the I2C_ISR + register. + 5 + 1 + + + BERRCF + Bus error flag clear Writing 1 to this + bit clears the BERRF flag in the I2C_ISR + register. + 8 + 1 + + + ARLOCF + Arbitration Lost flag clear Writing 1 to + this bit clears the ARLO flag in the I2C_ISR + register. + 9 + 1 + + + OVRCF + Overrun/Underrun flag clear Writing 1 to + this bit clears the OVR flag in the I2C_ISR + register. + 10 + 1 + + + PECCF + PEC Error flag clear Writing 1 to this + bit clears the PECERR flag in the I2C_ISR register. + Note: If the SMBus feature is not supported, this bit + is reserved and forced by hardware to 0. Please refer + to Section25.3: I2C implementation. + 11 + 1 + + + TIMOUTCF + Timeout detection flag clear Writing 1 + to this bit clears the TIMEOUT flag in the I2C_ISR + register. Note: If the SMBus feature is not + supported, this bit is reserved and forced by + hardware to 0. Please refer to Section25.3: I2C + implementation. + 12 + 1 + + + ALERTCF + Alert flag clear Writing 1 to this bit + clears the ALERT flag in the I2C_ISR register. Note: + If the SMBus feature is not supported, this bit is + reserved and forced by hardware to 0. Please refer to + Section25.3: I2C implementation. + 13 + 1 + + + + + PECR + PECR + Access: No wait states + 0x20 + 0x20 + read-only + 0x00000000 + + + PEC + Packet error checking register This + field contains the internal PEC when PECEN=1. The PEC + is cleared by hardware when PE=0. + 0 + 8 + + + + + RXDR + RXDR + Access: No wait states + 0x24 + 0x20 + read-only + 0x00000000 + + + RXDATA + 8-bit receive data Data byte received + from the I2C bus. + 0 + 8 + + + + + TXDR + TXDR + Access: No wait states + 0x28 + 0x20 + read-write + 0x00000000 + + + TXDATA + 8-bit transmit data Data byte to be + transmitted to the I2C bus. Note: These bits can be + written only when TXE=1. + 0 + 8 + + + + + + + I2C2 + 0x40005800 + + I2C2_EV + I2C2 event interrupt + 33 + + + I2C2_ER + I2C2 error interrupt + 34 + + + + I2C3 + 0x40005C00 + + I2C3_EV + I2C3 event interrupt + 72 + + + I2C3_ER + I2C3 error interrupt + 73 + + + + I2C4 + 0x58001C00 + + I2C4_EV + I2C4 event interrupt + 95 + + + I2C4_ER + I2C4 error interrupt + 96 + + + + GPIOA + GPIO + GPIO + 0x58020000 + + 0x0 + 0x400 + registers + + + + MODER + MODER + GPIO port mode register + 0x0 + 0x20 + read-write + 0xABFFFFFF + + + MODE0 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 0 + 2 + + + MODE1 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 2 + 2 + + + MODE2 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 4 + 2 + + + MODE3 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 6 + 2 + + + MODE4 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 8 + 2 + + + MODE5 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 10 + 2 + + + MODE6 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 12 + 2 + + + MODE7 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 14 + 2 + + + MODE8 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 16 + 2 + + + MODE9 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 18 + 2 + + + MODE10 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 20 + 2 + + + MODE11 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 22 + 2 + + + MODE12 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 24 + 2 + + + MODE13 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 26 + 2 + + + MODE14 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 28 + 2 + + + MODE15 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O mode. + 30 + 2 + + + + + OTYPER + OTYPER + GPIO port output type register + 0x4 + 0x20 + read-write + 0x00000000 + + + OT0 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 0 + 1 + + + OT1 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 1 + 1 + + + OT2 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 2 + 1 + + + OT3 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 3 + 1 + + + OT4 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 4 + 1 + + + OT5 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 5 + 1 + + + OT6 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 6 + 1 + + + OT7 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 7 + 1 + + + OT8 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 8 + 1 + + + OT9 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 9 + 1 + + + OT10 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 10 + 1 + + + OT11 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 11 + 1 + + + OT12 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 12 + 1 + + + OT13 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 13 + 1 + + + OT14 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 14 + 1 + + + OT15 + Port x configuration bits (y = 0..15) + These bits are written by software to configure the + I/O output type. + 15 + 1 + + + + + OSPEEDR + OSPEEDR + GPIO port output speed + register + 0x8 + 0x20 + read-write + 0x0C000000 + + + OSPEED0 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 0 + 2 + + + OSPEED1 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 2 + 2 + + + OSPEED2 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 4 + 2 + + + OSPEED3 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 6 + 2 + + + OSPEED4 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 8 + 2 + + + OSPEED5 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 10 + 2 + + + OSPEED6 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 12 + 2 + + + OSPEED7 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 14 + 2 + + + OSPEED8 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 16 + 2 + + + OSPEED9 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 18 + 2 + + + OSPEED10 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 20 + 2 + + + OSPEED11 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 22 + 2 + + + OSPEED12 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 24 + 2 + + + OSPEED13 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 26 + 2 + + + OSPEED14 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 28 + 2 + + + OSPEED15 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O output speed. Note: Refer to the + device datasheet for the frequency specifications and + the power supply and load conditions for each + speed. + 30 + 2 + + + + + PUPDR + PUPDR + GPIO port pull-up/pull-down + register + 0xC + 0x20 + read-write + 0x12100000 + + + PUPD0 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 0 + 2 + + + PUPD1 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 2 + 2 + + + PUPD2 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 4 + 2 + + + PUPD3 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 6 + 2 + + + PUPD4 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 8 + 2 + + + PUPD5 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 10 + 2 + + + PUPD6 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 12 + 2 + + + PUPD7 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 14 + 2 + + + PUPD8 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 16 + 2 + + + PUPD9 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 18 + 2 + + + PUPD10 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 20 + 2 + + + PUPD11 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 22 + 2 + + + PUPD12 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 24 + 2 + + + PUPD13 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 26 + 2 + + + PUPD14 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 28 + 2 + + + PUPD15 + [1:0]: Port x configuration bits (y = + 0..15) These bits are written by software to + configure the I/O pull-up or pull-down + 30 + 2 + + + + + IDR + IDR + GPIO port input data register + 0x10 + 0x20 + read-only + 0x00000000 + + + ID0 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 0 + 1 + + + ID1 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 1 + 1 + + + ID2 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 2 + 1 + + + ID3 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 3 + 1 + + + ID4 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 4 + 1 + + + ID5 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 5 + 1 + + + ID6 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 6 + 1 + + + ID7 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 7 + 1 + + + ID8 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 8 + 1 + + + ID9 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 9 + 1 + + + ID10 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 10 + 1 + + + ID11 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 11 + 1 + + + ID12 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 12 + 1 + + + ID13 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 13 + 1 + + + ID14 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 14 + 1 + + + ID15 + Port input data bit (y = 0..15) These + bits are read-only. They contain the input value of + the corresponding I/O port. + 15 + 1 + + + + + ODR + ODR + GPIO port output data register + 0x14 + 0x20 + read-write + 0x00000000 + + + OD0 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 0 + 1 + + + OD1 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 1 + 1 + + + OD2 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 2 + 1 + + + OD3 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 3 + 1 + + + OD4 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 4 + 1 + + + OD5 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 5 + 1 + + + OD6 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 6 + 1 + + + OD7 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 7 + 1 + + + OD8 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 8 + 1 + + + OD9 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 9 + 1 + + + OD10 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 10 + 1 + + + OD11 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 11 + 1 + + + OD12 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 12 + 1 + + + OD13 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 13 + 1 + + + OD14 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 14 + 1 + + + OD15 + Port output data bit These bits can be + read and written by software. Note: For atomic bit + set/reset, the OD bits can be individually set and/or + reset by writing to the GPIOx_BSRR or GPIOx_BRR + registers (x = A..F). + 15 + 1 + + + + + BSRR + BSRR + GPIO port bit set/reset + register + 0x18 + 0x20 + write-only + 0x00000000 + + + BS0 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 0 + 1 + + + BS1 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 1 + 1 + + + BS2 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 2 + 1 + + + BS3 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 3 + 1 + + + BS4 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 4 + 1 + + + BS5 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 5 + 1 + + + BS6 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 6 + 1 + + + BS7 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 7 + 1 + + + BS8 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 8 + 1 + + + BS9 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 9 + 1 + + + BS10 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 10 + 1 + + + BS11 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 11 + 1 + + + BS12 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 12 + 1 + + + BS13 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 13 + 1 + + + BS14 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 14 + 1 + + + BS15 + Port x set bit y (y= 0..15) These bits + are write-only. A read to these bits returns the + value 0x0000. + 15 + 1 + + + BR0 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 16 + 1 + + + BR1 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 17 + 1 + + + BR2 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 18 + 1 + + + BR3 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 19 + 1 + + + BR4 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 20 + 1 + + + BR5 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 21 + 1 + + + BR6 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 22 + 1 + + + BR7 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 23 + 1 + + + BR8 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 24 + 1 + + + BR9 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 25 + 1 + + + BR10 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 26 + 1 + + + BR11 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 27 + 1 + + + BR12 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 28 + 1 + + + BR13 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 29 + 1 + + + BR14 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 30 + 1 + + + BR15 + Port x reset bit y (y = 0..15) These + bits are write-only. A read to these bits returns the + value 0x0000. Note: If both BSx and BRx are set, BSx + has priority. + 31 + 1 + + + + + LCKR + LCKR + This register is used to lock the + configuration of the port bits when a correct write + sequence is applied to bit 16 (LCKK). The value of bits + [15:0] is used to lock the configuration of the GPIO. + During the write sequence, the value of LCKR[15:0] must + not change. When the LOCK sequence has been applied on a + port bit, the value of this port bit can no longer be + modified until the next MCU reset or peripheral reset.A + specific write sequence is used to write to the + GPIOx_LCKR register. Only word access (32-bit long) is + allowed during this locking sequence.Each lock bit + freezes a specific configuration register (control and + alternate function registers). + 0x1C + 0x20 + read-write + 0x00000000 + + + LCK0 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 0 + 1 + + + LCK1 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 1 + 1 + + + LCK2 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 2 + 1 + + + LCK3 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 3 + 1 + + + LCK4 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 4 + 1 + + + LCK5 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 5 + 1 + + + LCK6 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 6 + 1 + + + LCK7 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 7 + 1 + + + LCK8 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 8 + 1 + + + LCK9 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 9 + 1 + + + LCK10 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 10 + 1 + + + LCK11 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 11 + 1 + + + LCK12 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 12 + 1 + + + LCK13 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 13 + 1 + + + LCK14 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 14 + 1 + + + LCK15 + Port x lock bit y (y= 0..15) These bits + are read/write but can only be written when the LCKK + bit is 0. + 15 + 1 + + + LCKK + Lock key This bit can be read any time. + It can only be modified using the lock key write + sequence. LOCK key write sequence: WR LCKR[16] = 1 + + LCKR[15:0] WR LCKR[16] = 0 + LCKR[15:0] WR LCKR[16] = + 1 + LCKR[15:0] RD LCKR RD LCKR[16] = 1 (this read + operation is optional but it confirms that the lock + is active) Note: During the LOCK key write sequence, + the value of LCK[15:0] must not change. Any error in + the lock sequence aborts the lock. After the first + lock sequence on any bit of the port, any read access + on the LCKK bit will return 1 until the next MCU + reset or peripheral reset. + 16 + 1 + + + + + AFRL + AFRL + GPIO alternate function low + register + 0x20 + 0x20 + read-write + 0x00000000 + + + AFSEL0 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 0 + 4 + + + AFSEL1 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 4 + 4 + + + AFSEL2 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 8 + 4 + + + AFSEL3 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 12 + 4 + + + AFSEL4 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 16 + 4 + + + AFSEL5 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 20 + 4 + + + AFSEL6 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 24 + 4 + + + AFSEL7 + [3:0]: Alternate function selection for + port x pin y (y = 0..7) These bits are written by + software to configure alternate function I/Os AFSELy + selection: + 28 + 4 + + + + + AFRH + AFRH + GPIO alternate function high + register + 0x24 + 0x20 + read-write + 0x00000000 + + + AFSEL8 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 0 + 4 + + + AFSEL9 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 4 + 4 + + + AFSEL10 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 8 + 4 + + + AFSEL11 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 12 + 4 + + + AFSEL12 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 16 + 4 + + + AFSEL13 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 20 + 4 + + + AFSEL14 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 24 + 4 + + + AFSEL15 + [3:0]: Alternate function selection for + port x pin y (y = 8..15) These bits are written by + software to configure alternate function + I/Os + 28 + 4 + + + + + + + GPIOB + 0x58020400 + + + GPIOC + 0x58020800 + + + GPIOD + 0x58020C00 + + + GPIOE + 0x58021000 + + + GPIOF + 0x58021400 + + + GPIOG + 0x58021800 + + + GPIOH + 0x58021C00 + + + GPIOI + 0x58022000 + + + GPIOJ + 0x58022400 + + + GPIOK + 0x58022800 + + + JPEG + JPEG + JPEG + 0x52003000 + + 0x0 + 0x400 + registers + + + JPEG + JPEG global interrupt + 121 + + + + CONFR0 + CONFR0 + JPEG codec control register + 0x0 + 0x20 + write-only + 0x00000000 + + + START + Start This bit start or stop the + encoding or decoding process. Read this register + always return 0. + 0 + 1 + + + + + CONFR1 + CONFR1 + JPEG codec configuration register + 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + NF + Number of color components This field + defines the number of color components minus + 1. + 0 + 2 + + + DE + Decoding Enable This bit selects the + coding or decoding process + 3 + 1 + + + COLORSPACE + Color Space This filed defines the + number of quantization tables minus 1 to insert in + the output stream. + 4 + 2 + + + NS + Number of components for Scan This field + defines the number of components minus 1 for scan + header marker segment. + 6 + 2 + + + HDR + Header Processing This bit enable the + header processing (generation/parsing). + 8 + 1 + + + YSIZE + Y Size This field defines the number of + lines in source image. + 16 + 16 + + + + + CONFR2 + CONFR2 + JPEG codec configuration register + 2 + 0x8 + 0x20 + read-write + 0x00000000 + + + NMCU + Number of MCU For encoding: this field + defines the number of MCU units minus 1 to encode. + For decoding: this field indicates the number of + complete MCU units minus 1 to be decoded (this field + is updated after the JPEG header parsing). If the + decoded image size has not a X or Y size multiple of + 8 or 16 (depending on the sub-sampling process), the + resulting incomplete or empty MCU must be added to + this value to get the total number of MCU + generated. + 0 + 26 + + + + + CONFR3 + CONFR3 + JPEG codec configuration register + 3 + 0xC + 0x20 + read-write + 0x00000000 + + + XSIZE + X size This field defines the number of + pixels per line. + 16 + 16 + + + + + CONFRN1 + CONFRN1 + JPEG codec configuration register + 4-7 + 0x10 + 0x20 + read-write + 0x00000000 + + + HD + Huffman DC Selects the Huffman table for + encoding the DC coefficients. + 0 + 1 + + + HA + Huffman AC Selects the Huffman table for + encoding the AC coefficients. + 1 + 1 + + + QT + Quantization Table Selects quantization + table associated with a color + component. + 2 + 2 + + + NB + Number of Block Number of data units + minus 1 that belong to a particular color in the + MCU. + 4 + 4 + + + VSF + Vertical Sampling Factor Vertical + sampling factor for component i. + 8 + 4 + + + HSF + Horizontal Sampling Factor Horizontal + sampling factor for component i. + 12 + 4 + + + + + CONFRN2 + CONFRN2 + JPEG codec configuration register + 4-7 + 0x14 + 0x20 + read-write + 0x00000000 + + + HD + Huffman DC Selects the Huffman table for + encoding the DC coefficients. + 0 + 1 + + + HA + Huffman AC Selects the Huffman table for + encoding the AC coefficients. + 1 + 1 + + + QT + Quantization Table Selects quantization + table associated with a color + component. + 2 + 2 + + + NB + Number of Block Number of data units + minus 1 that belong to a particular color in the + MCU. + 4 + 4 + + + VSF + Vertical Sampling Factor Vertical + sampling factor for component i. + 8 + 4 + + + HSF + Horizontal Sampling Factor Horizontal + sampling factor for component i. + 12 + 4 + + + + + CONFRN3 + CONFRN3 + JPEG codec configuration register + 4-7 + 0x18 + 0x20 + read-write + 0x00000000 + + + HD + Huffman DC Selects the Huffman table for + encoding the DC coefficients. + 0 + 1 + + + HA + Huffman AC Selects the Huffman table for + encoding the AC coefficients. + 1 + 1 + + + QT + Quantization Table Selects quantization + table associated with a color + component. + 2 + 2 + + + NB + Number of Block Number of data units + minus 1 that belong to a particular color in the + MCU. + 4 + 4 + + + VSF + Vertical Sampling Factor Vertical + sampling factor for component i. + 8 + 4 + + + HSF + Horizontal Sampling Factor Horizontal + sampling factor for component i. + 12 + 4 + + + + + CONFRN4 + CONFRN4 + JPEG codec configuration register + 4-7 + 0x1C + 0x20 + read-write + 0x00000000 + + + HD + Huffman DC Selects the Huffman table for + encoding the DC coefficients. + 0 + 1 + + + HA + Huffman AC Selects the Huffman table for + encoding the AC coefficients. + 1 + 1 + + + QT + Quantization Table Selects quantization + table associated with a color + component. + 2 + 2 + + + NB + Number of Block Number of data units + minus 1 that belong to a particular color in the + MCU. + 4 + 4 + + + VSF + Vertical Sampling Factor Vertical + sampling factor for component i. + 8 + 4 + + + HSF + Horizontal Sampling Factor Horizontal + sampling factor for component i. + 12 + 4 + + + + + CR + CR + JPEG control register + 0x30 + 0x20 + read-write + 0x00000000 + + + JCEN + JPEG Core Enable Enable the JPEG codec + Core. + 0 + 1 + + + IFTIE + Input FIFO Threshold Interrupt Enable + This bit enables the interrupt generation when input + FIFO reach the threshold. + 1 + 1 + + + IFNFIE + Input FIFO Not Full Interrupt Enable + This bit enables the interrupt generation when input + FIFO is not empty. + 2 + 1 + + + OFTIE + Output FIFO Threshold Interrupt Enable + This bit enables the interrupt generation when output + FIFO reach the threshold. + 3 + 1 + + + OFNEIE + Output FIFO Not Empty Interrupt Enable + This bit enables the interrupt generation when output + FIFO is not empty. + 4 + 1 + + + EOCIE + End of Conversion Interrupt Enable This + bit enables the interrupt generation on the end of + conversion. + 5 + 1 + + + HPDIE + Header Parsing Done Interrupt Enable + This bit enables the interrupt generation on the + Header Parsing Operation. + 6 + 1 + + + IDMAEN + Input DMA Enable Enable the DMA request + generation for the input FIFO. + 11 + 1 + + + ODMAEN + Output DMA Enable Enable the DMA request + generation for the output FIFO. + 12 + 1 + + + IFF + Input FIFO Flush This bit flush the + input FIFO. This bit is always read as + 0. + 13 + 1 + + + OFF + Output FIFO Flush This bit flush the + output FIFO. This bit is always read as + 0. + 14 + 1 + + + + + SR + SR + JPEG status register + 0x34 + 0x20 + read-only + 0x00000006 + + + IFTF + Input FIFO Threshold Flag This bit is + set when the input FIFO is not full and is bellow its + threshold. + 1 + 1 + + + IFNFF + Input FIFO Not Full Flag This bit is set + when the input FIFO is not full (a data can be + written). + 2 + 1 + + + OFTF + Output FIFO Threshold Flag This bit is + set when the output FIFO is not empty and has reach + its threshold. + 3 + 1 + + + OFNEF + Output FIFO Not Empty Flag This bit is + set when the output FIFO is not empty (a data is + available). + 4 + 1 + + + EOCF + End of Conversion Flag This bit is set + when the JPEG codec core has finished the encoding or + the decoding process and than last data has been sent + to the output FIFO. + 5 + 1 + + + HPDF + Header Parsing Done Flag This bit is set + in decode mode when the JPEG codec has finished the + parsing of the headers and the internal registers + have been updated. + 6 + 1 + + + COF + Codec Operation Flag This bit is set + when when a JPEG codec operation is on going + (encoding or decoding). + 7 + 1 + + + + + CFR + CFR + JPEG clear flag register + 0x38 + 0x20 + read-write + 0x00000000 + + + CEOCF + Clear End of Conversion Flag Writing 1 + clears the End of Conversion Flag of the JPEG Status + Register. + 5 + 1 + + + CHPDF + Clear Header Parsing Done Flag Writing 1 + clears the Header Parsing Done Flag of the JPEG + Status Register. + 6 + 1 + + + + + DIR + DIR + JPEG data input register + 0x40 + 0x20 + write-only + 0x00000000 + + + DATAIN + Data Input FIFO Input FIFO data + register. + 0 + 32 + + + + + DOR + DOR + JPEG data output register + 0x44 + 0x20 + read-only + 0x00000000 + + + DATAOUT + Data Output FIFO Output FIFO data + register. + 0 + 32 + + + + + + + MDMA + MDMA + MDMA + 0x52000000 + + 0x0 + 0x1000 + registers + + + MDMA + MDMA + 122 + + + + MDMA_GISR0 + MDMA_GISR0 + MDMA Global Interrupt/Status + Register + 0x0 + 0x20 + read-only + 0x00000000 + + + GIF0 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 0 + 1 + + + GIF1 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 1 + 1 + + + GIF2 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 2 + 1 + + + GIF3 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 3 + 1 + + + GIF4 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 4 + 1 + + + GIF5 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 5 + 1 + + + GIF6 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 6 + 1 + + + GIF7 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 7 + 1 + + + GIF8 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 8 + 1 + + + GIF9 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 9 + 1 + + + GIF10 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 10 + 1 + + + GIF11 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 11 + 1 + + + GIF12 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 12 + 1 + + + GIF13 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 13 + 1 + + + GIF14 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 14 + 1 + + + GIF15 + Channel x global interrupt flag (x=...) + This bit is set and reset by hardware. It is a + logical OR of all the Channel x interrupt flags + (CTCIFx, BTIFx, BRTIFx, TEIFx) which are enabled in + the interrupt mask register (CTCIEx, BTIEx, BRTIEx, + TEIEx) + 15 + 1 + + + + + MDMA_C0ISR + MDMA_C0ISR + MDMA channel x interrupt/status + register + 0x40 + 0x20 + read-only + 0x00000000 + + + TEIF0 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF0 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF0 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF0 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF0 + channel x buffer transfer + complete + 4 + 1 + + + CRQA0 + channel x request active + flag + 16 + 1 + + + + + MDMA_C0IFCR + MDMA_C0IFCR + MDMA channel x interrupt flag clear + register + 0x44 + 0x20 + write-only + 0x00000000 + + + CTEIF0 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF0 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF0 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF0 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF0 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C0ESR + MDMA_C0ESR + MDMA Channel x error status + register + 0x48 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C0CR + MDMA_C0CR + This register is used to control the + concerned channel. + 0x4C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C0TCR + MDMA_C0TCR + This register is used to configure the + concerned channel. + 0x50 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C0BNDTR + MDMA_C0BNDTR + MDMA Channel x block number of data + register + 0x54 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C0SAR + MDMA_C0SAR + MDMA channel x source address + register + 0x58 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C0DAR + MDMA_C0DAR + MDMA channel x destination address + register + 0x5C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C0BRUR + MDMA_C0BRUR + MDMA channel x Block Repeat address Update + register + 0x60 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C0LAR + MDMA_C0LAR + MDMA channel x Link Address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C0TBR + MDMA_C0TBR + MDMA channel x Trigger and Bus selection + Register + 0x68 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C0MAR + MDMA_C0MAR + MDMA channel x Mask address + register + 0x70 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C0MDR + MDMA_C0MDR + MDMA channel x Mask Data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C1ISR + MDMA_C1ISR + MDMA channel x interrupt/status + register + 0x80 + 0x20 + read-only + 0x00000000 + + + TEIF1 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF1 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF1 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF1 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF1 + channel x buffer transfer + complete + 4 + 1 + + + CRQA1 + channel x request active + flag + 16 + 1 + + + + + MDMA_C1IFCR + MDMA_C1IFCR + MDMA channel x interrupt flag clear + register + 0x84 + 0x20 + write-only + 0x00000000 + + + CTEIF1 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF1 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF1 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF1 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF1 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C1ESR + MDMA_C1ESR + MDMA Channel x error status + register + 0x88 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C1CR + MDMA_C1CR + This register is used to control the + concerned channel. + 0x8C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C1TCR + MDMA_C1TCR + This register is used to configure the + concerned channel. + 0x90 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C1BNDTR + MDMA_C1BNDTR + MDMA Channel x block number of data + register + 0x94 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C1SAR + MDMA_C1SAR + MDMA channel x source address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C1DAR + MDMA_C1DAR + MDMA channel x destination address + register + 0x9C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C1BRUR + MDMA_C1BRUR + MDMA channel x Block Repeat address Update + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C1LAR + MDMA_C1LAR + MDMA channel x Link Address + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C1TBR + MDMA_C1TBR + MDMA channel x Trigger and Bus selection + Register + 0xA8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C1MAR + MDMA_C1MAR + MDMA channel x Mask address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C1MDR + MDMA_C1MDR + MDMA channel x Mask Data + register + 0xB4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C2ISR + MDMA_C2ISR + MDMA channel x interrupt/status + register + 0xC0 + 0x20 + read-only + 0x00000000 + + + TEIF2 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF2 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF2 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF2 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF2 + channel x buffer transfer + complete + 4 + 1 + + + CRQA2 + channel x request active + flag + 16 + 1 + + + + + MDMA_C2IFCR + MDMA_C2IFCR + MDMA channel x interrupt flag clear + register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CTEIF2 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF2 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF2 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF2 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF2 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C2ESR + MDMA_C2ESR + MDMA Channel x error status + register + 0xC8 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C2CR + MDMA_C2CR + This register is used to control the + concerned channel. + 0xCC + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C2TCR + MDMA_C2TCR + This register is used to configure the + concerned channel. + 0xD0 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C2BNDTR + MDMA_C2BNDTR + MDMA Channel x block number of data + register + 0xD4 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C2SAR + MDMA_C2SAR + MDMA channel x source address + register + 0xD8 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C2DAR + MDMA_C2DAR + MDMA channel x destination address + register + 0xDC + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C2BRUR + MDMA_C2BRUR + MDMA channel x Block Repeat address Update + register + 0xE0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C2LAR + MDMA_C2LAR + MDMA channel x Link Address + register + 0xE4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C2TBR + MDMA_C2TBR + MDMA channel x Trigger and Bus selection + Register + 0xE8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C2MAR + MDMA_C2MAR + MDMA channel x Mask address + register + 0xF0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C2MDR + MDMA_C2MDR + MDMA channel x Mask Data + register + 0xF4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C3ISR + MDMA_C3ISR + MDMA channel x interrupt/status + register + 0x100 + 0x20 + read-only + 0x00000000 + + + TEIF3 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF3 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF3 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF3 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF3 + channel x buffer transfer + complete + 4 + 1 + + + CRQA3 + channel x request active + flag + 16 + 1 + + + + + MDMA_C3IFCR + MDMA_C3IFCR + MDMA channel x interrupt flag clear + register + 0x104 + 0x20 + write-only + 0x00000000 + + + CTEIF3 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF3 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF3 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF3 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF3 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C3ESR + MDMA_C3ESR + MDMA Channel x error status + register + 0x108 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C3CR + MDMA_C3CR + This register is used to control the + concerned channel. + 0x10C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C3TCR + MDMA_C3TCR + This register is used to configure the + concerned channel. + 0x110 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C3BNDTR + MDMA_C3BNDTR + MDMA Channel x block number of data + register + 0x114 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C3SAR + MDMA_C3SAR + MDMA channel x source address + register + 0x118 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C3DAR + MDMA_C3DAR + MDMA channel x destination address + register + 0x11C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C3BRUR + MDMA_C3BRUR + MDMA channel x Block Repeat address Update + register + 0x120 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C3LAR + MDMA_C3LAR + MDMA channel x Link Address + register + 0x124 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C3TBR + MDMA_C3TBR + MDMA channel x Trigger and Bus selection + Register + 0x128 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C3MAR + MDMA_C3MAR + MDMA channel x Mask address + register + 0x130 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C3MDR + MDMA_C3MDR + MDMA channel x Mask Data + register + 0x134 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C4ISR + MDMA_C4ISR + MDMA channel x interrupt/status + register + 0x140 + 0x20 + read-only + 0x00000000 + + + TEIF4 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF4 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF4 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF4 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF4 + channel x buffer transfer + complete + 4 + 1 + + + CRQA4 + channel x request active + flag + 16 + 1 + + + + + MDMA_C4IFCR + MDMA_C4IFCR + MDMA channel x interrupt flag clear + register + 0x144 + 0x20 + write-only + 0x00000000 + + + CTEIF4 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF4 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF4 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF4 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF4 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C4ESR + MDMA_C4ESR + MDMA Channel x error status + register + 0x148 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C4CR + MDMA_C4CR + This register is used to control the + concerned channel. + 0x14C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C4TCR + MDMA_C4TCR + This register is used to configure the + concerned channel. + 0x150 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C4BNDTR + MDMA_C4BNDTR + MDMA Channel x block number of data + register + 0x154 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C4SAR + MDMA_C4SAR + MDMA channel x source address + register + 0x158 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C4DAR + MDMA_C4DAR + MDMA channel x destination address + register + 0x15C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C4BRUR + MDMA_C4BRUR + MDMA channel x Block Repeat address Update + register + 0x160 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C4LAR + MDMA_C4LAR + MDMA channel x Link Address + register + 0x164 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C4TBR + MDMA_C4TBR + MDMA channel x Trigger and Bus selection + Register + 0x168 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C4MAR + MDMA_C4MAR + MDMA channel x Mask address + register + 0x170 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C4MDR + MDMA_C4MDR + MDMA channel x Mask Data + register + 0x174 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C5ISR + MDMA_C5ISR + MDMA channel x interrupt/status + register + 0x180 + 0x20 + read-only + 0x00000000 + + + TEIF5 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF5 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF5 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF5 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF5 + channel x buffer transfer + complete + 4 + 1 + + + CRQA5 + channel x request active + flag + 16 + 1 + + + + + MDMA_C5IFCR + MDMA_C5IFCR + MDMA channel x interrupt flag clear + register + 0x184 + 0x20 + write-only + 0x00000000 + + + CTEIF5 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF5 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF5 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF5 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF5 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C5ESR + MDMA_C5ESR + MDMA Channel x error status + register + 0x188 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C5CR + MDMA_C5CR + This register is used to control the + concerned channel. + 0x18C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C5TCR + MDMA_C5TCR + This register is used to configure the + concerned channel. + 0x190 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C5BNDTR + MDMA_C5BNDTR + MDMA Channel x block number of data + register + 0x194 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C5SAR + MDMA_C5SAR + MDMA channel x source address + register + 0x198 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C5DAR + MDMA_C5DAR + MDMA channel x destination address + register + 0x19C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C5BRUR + MDMA_C5BRUR + MDMA channel x Block Repeat address Update + register + 0x1A0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C5LAR + MDMA_C5LAR + MDMA channel x Link Address + register + 0x1A4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C5TBR + MDMA_C5TBR + MDMA channel x Trigger and Bus selection + Register + 0x1A8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C5MAR + MDMA_C5MAR + MDMA channel x Mask address + register + 0x1B0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C5MDR + MDMA_C5MDR + MDMA channel x Mask Data + register + 0x1B4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C6ISR + MDMA_C6ISR + MDMA channel x interrupt/status + register + 0x1C0 + 0x20 + read-only + 0x00000000 + + + TEIF6 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF6 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF6 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF6 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF6 + channel x buffer transfer + complete + 4 + 1 + + + CRQA6 + channel x request active + flag + 16 + 1 + + + + + MDMA_C6IFCR + MDMA_C6IFCR + MDMA channel x interrupt flag clear + register + 0x1C4 + 0x20 + write-only + 0x00000000 + + + CTEIF6 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF6 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF6 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF6 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF6 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C6ESR + MDMA_C6ESR + MDMA Channel x error status + register + 0x1C8 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C6CR + MDMA_C6CR + This register is used to control the + concerned channel. + 0x1CC + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C6TCR + MDMA_C6TCR + This register is used to configure the + concerned channel. + 0x1D0 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C6BNDTR + MDMA_C6BNDTR + MDMA Channel x block number of data + register + 0x1D4 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0 + 20 + 12 + + + + + MDMA_C6SAR + MDMA_C6SAR + MDMA channel x source address + register + 0x1D8 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C6DAR + MDMA_C6DAR + MDMA channel x destination address + register + 0x1DC + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C6BRUR + MDMA_C6BRUR + MDMA channel x Block Repeat address Update + register + 0x1E0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C6LAR + MDMA_C6LAR + MDMA channel x Link Address + register + 0x1E4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C6TBR + MDMA_C6TBR + MDMA channel x Trigger and Bus selection + Register + 0x1E8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C6MAR + MDMA_C6MAR + MDMA channel x Mask address + register + 0x1F0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C6MDR + MDMA_C6MDR + MDMA channel x Mask Data + register + 0x1F4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C7ISR + MDMA_C7ISR + MDMA channel x interrupt/status + register + 0x200 + 0x20 + read-only + 0x00000000 + + + TEIF7 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF7 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF7 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF7 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF7 + channel x buffer transfer + complete + 4 + 1 + + + CRQA7 + channel x request active + flag + 16 + 1 + + + + + MDMA_C7IFCR + MDMA_C7IFCR + MDMA channel x interrupt flag clear + register + 0x204 + 0x20 + write-only + 0x00000000 + + + CTEIF7 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF7 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF7 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF7 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF7 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C7ESR + MDMA_C7ESR + MDMA Channel x error status + register + 0x208 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C7CR + MDMA_C7CR + This register is used to control the + concerned channel. + 0x20C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C7TCR + MDMA_C7TCR + This register is used to configure the + concerned channel. + 0x210 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C7BNDTR + MDMA_C7BNDTR + MDMA Channel x block number of data + register + 0x214 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C7SAR + MDMA_C7SAR + MDMA channel x source address + register + 0x218 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C7DAR + MDMA_C7DAR + MDMA channel x destination address + register + 0x21C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C7BRUR + MDMA_C7BRUR + MDMA channel x Block Repeat address Update + register + 0x220 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C7LAR + MDMA_C7LAR + MDMA channel x Link Address + register + 0x224 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C7TBR + MDMA_C7TBR + MDMA channel x Trigger and Bus selection + Register + 0x228 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C7MAR + MDMA_C7MAR + MDMA channel x Mask address + register + 0x230 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C7MDR + MDMA_C7MDR + MDMA channel x Mask Data + register + 0x234 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C8ISR + MDMA_C8ISR + MDMA channel x interrupt/status + register + 0x240 + 0x20 + read-only + 0x00000000 + + + TEIF8 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF8 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF8 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF8 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF8 + channel x buffer transfer + complete + 4 + 1 + + + CRQA8 + channel x request active + flag + 16 + 1 + + + + + MDMA_C8IFCR + MDMA_C8IFCR + MDMA channel x interrupt flag clear + register + 0x244 + 0x20 + write-only + 0x00000000 + + + CTEIF8 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF8 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF8 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF8 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF8 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C8ESR + MDMA_C8ESR + MDMA Channel x error status + register + 0x248 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C8CR + MDMA_C8CR + This register is used to control the + concerned channel. + 0x24C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C8TCR + MDMA_C8TCR + This register is used to configure the + concerned channel. + 0x250 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C8BNDTR + MDMA_C8BNDTR + MDMA Channel x block number of data + register + 0x254 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C8SAR + MDMA_C8SAR + MDMA channel x source address + register + 0x258 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C8DAR + MDMA_C8DAR + MDMA channel x destination address + register + 0x25C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C8BRUR + MDMA_C8BRUR + MDMA channel x Block Repeat address Update + register + 0x260 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C8LAR + MDMA_C8LAR + MDMA channel x Link Address + register + 0x264 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C8TBR + MDMA_C8TBR + MDMA channel x Trigger and Bus selection + Register + 0x268 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C8MAR + MDMA_C8MAR + MDMA channel x Mask address + register + 0x270 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C8MDR + MDMA_C8MDR + MDMA channel x Mask Data + register + 0x274 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C9ISR + MDMA_C9ISR + MDMA channel x interrupt/status + register + 0x280 + 0x20 + read-only + 0x00000000 + + + TEIF9 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF9 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF9 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF9 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF9 + channel x buffer transfer + complete + 4 + 1 + + + CRQA9 + channel x request active + flag + 16 + 1 + + + + + MDMA_C9IFCR + MDMA_C9IFCR + MDMA channel x interrupt flag clear + register + 0x284 + 0x20 + write-only + 0x00000000 + + + CTEIF9 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF9 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF9 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF9 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF9 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C9ESR + MDMA_C9ESR + MDMA Channel x error status + register + 0x288 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C9CR + MDMA_C9CR + This register is used to control the + concerned channel. + 0x28C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C9TCR + MDMA_C9TCR + This register is used to configure the + concerned channel. + 0x290 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C9BNDTR + MDMA_C9BNDTR + MDMA Channel x block number of data + register + 0x294 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C9SAR + MDMA_C9SAR + MDMA channel x source address + register + 0x298 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C9DAR + MDMA_C9DAR + MDMA channel x destination address + register + 0x29C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C9BRUR + MDMA_C9BRUR + MDMA channel x Block Repeat address Update + register + 0x2A0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C9LAR + MDMA_C9LAR + MDMA channel x Link Address + register + 0x2A4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C9TBR + MDMA_C9TBR + MDMA channel x Trigger and Bus selection + Register + 0x2A8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C9MAR + MDMA_C9MAR + MDMA channel x Mask address + register + 0x2B0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C9MDR + MDMA_C9MDR + MDMA channel x Mask Data + register + 0x2B4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C10ISR + MDMA_C10ISR + MDMA channel x interrupt/status + register + 0x2C0 + 0x20 + read-only + 0x00000000 + + + TEIF10 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF10 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF10 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF10 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF10 + channel x buffer transfer + complete + 4 + 1 + + + CRQA10 + channel x request active + flag + 16 + 1 + + + + + MDMA_C10IFCR + MDMA_C10IFCR + MDMA channel x interrupt flag clear + register + 0x2C4 + 0x20 + write-only + 0x00000000 + + + CTEIF10 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF10 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF10 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF10 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF10 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C10ESR + MDMA_C10ESR + MDMA Channel x error status + register + 0x2C8 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C10CR + MDMA_C10CR + This register is used to control the + concerned channel. + 0x2CC + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C10TCR + MDMA_C10TCR + This register is used to configure the + concerned channel. + 0x2D0 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C10BNDTR + MDMA_C10BNDTR + MDMA Channel x block number of data + register + 0x2D4 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C10SAR + MDMA_C10SAR + MDMA channel x source address + register + 0x2D8 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C10DAR + MDMA_C10DAR + MDMA channel x destination address + register + 0x2DC + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C10BRUR + MDMA_C10BRUR + MDMA channel x Block Repeat address Update + register + 0x2E0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C10LAR + MDMA_C10LAR + MDMA channel x Link Address + register + 0x2E4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C10TBR + MDMA_C10TBR + MDMA channel x Trigger and Bus selection + Register + 0x2E8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C10MAR + MDMA_C10MAR + MDMA channel x Mask address + register + 0x2F0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C10MDR + MDMA_C10MDR + MDMA channel x Mask Data + register + 0x2F4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C11ISR + MDMA_C11ISR + MDMA channel x interrupt/status + register + 0x300 + 0x20 + read-only + 0x00000000 + + + TEIF11 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF11 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF11 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF11 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF11 + channel x buffer transfer + complete + 4 + 1 + + + CRQA11 + channel x request active + flag + 16 + 1 + + + + + MDMA_C11IFCR + MDMA_C11IFCR + MDMA channel x interrupt flag clear + register + 0x304 + 0x20 + write-only + 0x00000000 + + + CTEIF11 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF11 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF11 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF11 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF11 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C11ESR + MDMA_C11ESR + MDMA Channel x error status + register + 0x308 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C11CR + MDMA_C11CR + This register is used to control the + concerned channel. + 0x30C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C11TCR + MDMA_C11TCR + This register is used to configure the + concerned channel. + 0x310 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C11BNDTR + MDMA_C11BNDTR + MDMA Channel x block number of data + register + 0x314 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C11SAR + MDMA_C11SAR + MDMA channel x source address + register + 0x318 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C11DAR + MDMA_C11DAR + MDMA channel x destination address + register + 0x31C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C11BRUR + MDMA_C11BRUR + MDMA channel x Block Repeat address Update + register + 0x320 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C11LAR + MDMA_C11LAR + MDMA channel x Link Address + register + 0x324 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C11TBR + MDMA_C11TBR + MDMA channel x Trigger and Bus selection + Register + 0x328 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C11MAR + MDMA_C11MAR + MDMA channel x Mask address + register + 0x330 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C11MDR + MDMA_C11MDR + MDMA channel x Mask Data + register + 0x334 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C12ISR + MDMA_C12ISR + MDMA channel x interrupt/status + register + 0x340 + 0x20 + read-only + 0x00000000 + + + TEIF12 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF12 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF12 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF12 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF12 + channel x buffer transfer + complete + 4 + 1 + + + CRQA12 + channel x request active + flag + 16 + 1 + + + + + MDMA_C12IFCR + MDMA_C12IFCR + MDMA channel x interrupt flag clear + register + 0x344 + 0x20 + write-only + 0x00000000 + + + CTEIF12 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF12 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF12 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF12 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF12 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C12ESR + MDMA_C12ESR + MDMA Channel x error status + register + 0x348 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C12CR + MDMA_C12CR + This register is used to control the + concerned channel. + 0x34C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C12TCR + MDMA_C12TCR + This register is used to configure the + concerned channel. + 0x350 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C12BNDTR + MDMA_C12BNDTR + MDMA Channel x block number of data + register + 0x354 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C12SAR + MDMA_C12SAR + MDMA channel x source address + register + 0x358 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C12DAR + MDMA_C12DAR + MDMA channel x destination address + register + 0x35C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C12BRUR + MDMA_C12BRUR + MDMA channel x Block Repeat address Update + register + 0x360 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C12LAR + MDMA_C12LAR + MDMA channel x Link Address + register + 0x364 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C12TBR + MDMA_C12TBR + MDMA channel x Trigger and Bus selection + Register + 0x368 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C12MAR + MDMA_C12MAR + MDMA channel x Mask address + register + 0x370 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C12MDR + MDMA_C12MDR + MDMA channel x Mask Data + register + 0x374 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C13ISR + MDMA_C13ISR + MDMA channel x interrupt/status + register + 0x380 + 0x20 + read-only + 0x00000000 + + + TEIF13 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF13 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF13 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF13 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF13 + channel x buffer transfer + complete + 4 + 1 + + + CRQA13 + channel x request active + flag + 16 + 1 + + + + + MDMA_C13IFCR + MDMA_C13IFCR + MDMA channel x interrupt flag clear + register + 0x384 + 0x20 + write-only + 0x00000000 + + + CTEIF13 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF13 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF13 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF13 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF13 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C13ESR + MDMA_C13ESR + MDMA Channel x error status + register + 0x388 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C13CR + MDMA_C13CR + This register is used to control the + concerned channel. + 0x38C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C13TCR + MDMA_C13TCR + This register is used to configure the + concerned channel. + 0x390 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C13BNDTR + MDMA_C13BNDTR + MDMA Channel x block number of data + register + 0x394 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C13SAR + MDMA_C13SAR + MDMA channel x source address + register + 0x398 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C13DAR + MDMA_C13DAR + MDMA channel x destination address + register + 0x39C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C13BRUR + MDMA_C13BRUR + MDMA channel x Block Repeat address Update + register + 0x3A0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C13LAR + MDMA_C13LAR + MDMA channel x Link Address + register + 0x3A4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C13TBR + MDMA_C13TBR + MDMA channel x Trigger and Bus selection + Register + 0x3A8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C13MAR + MDMA_C13MAR + MDMA channel x Mask address + register + 0x3B0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C13MDR + MDMA_C13MDR + MDMA channel x Mask Data + register + 0x3B4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C14ISR + MDMA_C14ISR + MDMA channel x interrupt/status + register + 0x3C0 + 0x20 + read-only + 0x00000000 + + + TEIF14 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF14 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF14 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF14 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF14 + channel x buffer transfer + complete + 4 + 1 + + + CRQA14 + channel x request active + flag + 16 + 1 + + + + + MDMA_C14IFCR + MDMA_C14IFCR + MDMA channel x interrupt flag clear + register + 0x3C4 + 0x20 + write-only + 0x00000000 + + + CTEIF14 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF14 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF14 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF14 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF14 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C14ESR + MDMA_C14ESR + MDMA Channel x error status + register + 0x3C8 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C14CR + MDMA_C14CR + This register is used to control the + concerned channel. + 0x3CC + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C14TCR + MDMA_C14TCR + This register is used to configure the + concerned channel. + 0x3D0 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C14BNDTR + MDMA_C14BNDTR + MDMA Channel x block number of data + register + 0x3D4 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C14SAR + MDMA_C14SAR + MDMA channel x source address + register + 0x3D8 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C14DAR + MDMA_C14DAR + MDMA channel x destination address + register + 0x3DC + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C14BRUR + MDMA_C14BRUR + MDMA channel x Block Repeat address Update + register + 0x3E0 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C14LAR + MDMA_C14LAR + MDMA channel x Link Address + register + 0x3E4 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C14TBR + MDMA_C14TBR + MDMA channel x Trigger and Bus selection + Register + 0x3E8 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C14MAR + MDMA_C14MAR + MDMA channel x Mask address + register + 0x3F0 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C14MDR + MDMA_C14MDR + MDMA channel x Mask Data + register + 0x3F4 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + MDMA_C15ISR + MDMA_C15ISR + MDMA channel x interrupt/status + register + 0x400 + 0x20 + read-only + 0x00000000 + + + TEIF15 + Channel x transfer error interrupt flag + This bit is set by hardware. It is cleared by + software writing 1 to the corresponding bit in the + DMA_IFCRy register. + 0 + 1 + + + CTCIF15 + Channel x Channel Transfer Complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. CTC is set when the + last block was transferred and the channel has been + automatically disabled. CTC is also set when the + channel is suspended, as a result of writing EN bit + to 0. + 1 + 1 + + + BRTIF15 + Channel x block repeat transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 2 + 1 + + + BTIF15 + Channel x block transfer complete + interrupt flag This bit is set by hardware. It is + cleared by software writing 1 to the corresponding + bit in the DMA_IFCRy register. + 3 + 1 + + + TCIF15 + channel x buffer transfer + complete + 4 + 1 + + + CRQA15 + channel x request active + flag + 16 + 1 + + + + + MDMA_C15IFCR + MDMA_C15IFCR + MDMA channel x interrupt flag clear + register + 0x404 + 0x20 + write-only + 0x00000000 + + + CTEIF15 + Channel x clear transfer error interrupt + flag Writing a 1 into this bit clears TEIFx in the + MDMA_ISRy register + 0 + 1 + + + CCTCIF15 + Clear Channel transfer complete + interrupt flag for channel x Writing a 1 into this + bit clears CTCIFx in the MDMA_ISRy + register + 1 + 1 + + + CBRTIF15 + Channel x clear block repeat transfer + complete interrupt flag Writing a 1 into this bit + clears BRTIFx in the MDMA_ISRy register + 2 + 1 + + + CBTIF15 + Channel x Clear block transfer complete + interrupt flag Writing a 1 into this bit clears BTIFx + in the MDMA_ISRy register + 3 + 1 + + + CLTCIF15 + CLear buffer Transfer Complete Interrupt + Flag for channel x Writing a 1 into this bit clears + TCIFx in the MDMA_ISRy register + 4 + 1 + + + + + MDMA_C15ESR + MDMA_C15ESR + MDMA Channel x error status + register + 0x408 + 0x20 + read-only + 0x00000000 + + + TEA + Transfer Error Address These bits are + set and cleared by HW, in case of an MDMA data + transfer error. It is used in conjunction with TED. + This field indicates the 7 LSBits of the address + which generated a transfer/access error. It may be + used by SW to retrieve the failing address, by adding + this value (truncated to the buffer transfer length + size) to the current SAR/DAR value. Note: The SAR/DAR + current value doesnt reflect this last address due to + the FIFO management system. The SAR/DAR are only + updated at the end of a (buffer) transfer (of TLEN+1 + bytes). Note: It is not set in case of a link data + error. + 0 + 7 + + + TED + Transfer Error Direction These bit is + set and cleared by HW, in case of an MDMA data + transfer error. + 7 + 1 + + + TELD + Transfer Error Link Data These bit is + set by HW, in case of a transfer error while reading + the block link data structure. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 8 + 1 + + + TEMD + Transfer Error Mask Data These bit is + set by HW, in case of a transfer error while writing + the Mask Data. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 9 + 1 + + + ASE + Address/Size Error These bit is set by + HW, when the programmed address is not aligned with + the data size. TED will indicate whether the problem + is on the source or destination. It is cleared by + software writing 1 to the CTEIFx bit in the DMA_IFCRy + register. + 10 + 1 + + + BSE + Block Size Error These bit is set by HW, + when the block size is not an integer multiple of the + data size either for source or destination. TED will + indicate whether the problem is on the source or + destination. It is cleared by software writing 1 to + the CTEIFx bit in the DMA_IFCRy + register. + 11 + 1 + + + + + MDMA_C15CR + MDMA_C15CR + This register is used to control the + concerned channel. + 0x40C + 0x20 + 0x00000000 + + + EN + channel enable + 0 + 1 + read-write + + + TEIE + Transfer error interrupt enable This bit + is set and cleared by software. + 1 + 1 + read-write + + + CTCIE + Channel Transfer Complete interrupt + enable This bit is set and cleared by + software. + 2 + 1 + read-write + + + BRTIE + Block Repeat transfer interrupt enable + This bit is set and cleared by + software. + 3 + 1 + read-write + + + BTIE + Block Transfer interrupt enable This bit + is set and cleared by software. + 4 + 1 + read-write + + + TCIE + buffer Transfer Complete interrupt + enable This bit is set and cleared by + software. + 5 + 1 + read-write + + + PL + Priority level These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0. + 6 + 2 + read-write + + + BEX + byte Endianness exchange + 12 + 1 + read-write + + + HEX + Half word Endianes + exchange + 13 + 1 + read-write + + + WEX + Word Endianness exchange + 14 + 1 + read-write + + + SWRQ + SW ReQuest Writing a 1 into this bit + sets the CRQAx in MDMA_ISRy register, activating the + request on Channel x Note: Either the whole CxCR + register or the 8-bit/16-bit register @ Address + offset: 0x4E + 0x40 chn may be used for SWRQ + activation. In case of a SW request, acknowledge is + not generated (neither HW signal, nor CxMAR write + access). + 16 + 1 + write-only + + + + + MDMA_C15TCR + MDMA_C15TCR + This register is used to configure the + concerned channel. + 0x410 + 0x20 + read-write + 0x00000000 + + + SINC + Source increment mode These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0 Note: When source is + AHB (SBUS=1), SINC = 00 is forbidden. In Linked List + Mode, at the end of a block (single or last block in + repeated block transfer mode), this register will be + loaded from memory (from address given by current + LAR[31:0] + 0x00). + 0 + 2 + + + DINC + Destination increment mode These bits + are set and cleared by software. These bits are + protected and can be written only if EN is 0 Note: + When destination is AHB (DBUS=1), DINC = 00 is + forbidden. + 2 + 2 + + + SSIZE + Source data size These bits are set and + cleared by software. These bits are protected and can + be written only if EN is 0 Note: If a value of 11 is + programmed for the TCM access/AHB port, a transfer + error will occur (TEIF bit set) If SINCOS &lt; + SSIZE and SINC &#8800; 00, the result will be + unpredictable. Note: SSIZE = 11 (double-word) is + forbidden when source is TCM/AHB bus + (SBUS=1). + 4 + 2 + + + DSIZE + Destination data size These bits are set + and cleared by software. These bits are protected and + can be written only if EN is 0. Note: If a value of + 11 is programmed for the TCM access/AHB port, a + transfer error will occur (TEIF bit set) If DINCOS + &lt; DSIZE and DINC &#8800; 00, the result + will be unpredictable. Note: DSIZE = 11 (double-word) + is forbidden when destination is TCM/AHB bus + (DBUS=1). + 6 + 2 + + + SINCOS + source increment offset + size + 8 + 2 + + + DINCOS + Destination increment + offset + 10 + 2 + + + SBURST + source burst transfer + configuration + 12 + 3 + + + DBURST + Destination burst transfer + configuration + 15 + 3 + + + TLEN + buffer transfer lengh + 18 + 7 + + + PKE + PacK Enable These bit is set and cleared + by software. If the Source Size is smaller than the + destination, it will be padded according to the PAM + value. If the Source data size is larger than the + destination one, it will be truncated. The alignment + will be done according to the PAM[0] value. This bit + is protected and can be written only if EN is + 0 + 25 + 1 + + + PAM + Padding/Alignement Mode These bits are + set and cleared by software. Case 1: Source data size + smaller than destination data size - 3 options are + valid. Case 2: Source data size larger than + destination data size. The remainder part is + discarded. When PKE = 1 or DSIZE=SSIZE, these bits + are ignored. These bits are protected and can be + written only if EN is 0 + 26 + 2 + + + TRGM + Trigger Mode These bits are set and + cleared by software. Note: If TRGM is 11 for the + current block, all the values loaded at the end of + the current block through the linked list mechanism + must keep the same value (TRGM=11) and the same SWRM + value, otherwise the result is undefined. These bits + are protected and can be written only if EN is + 0. + 28 + 2 + + + SWRM + SW Request Mode This bit is set and + cleared by software. If a HW or SW request is + currently active, the bit change will be delayed + until the current transfer is completed. If the CxMAR + contains a valid address, the CxMDR value will also + be written @ CxMAR address. This bit is protected and + can be written only if EN is 0. + 30 + 1 + + + BWM + Bufferable Write Mode This bit is set + and cleared by software. This bit is protected and + can be written only if EN is 0. Note: All MDMA + destination accesses are non-cacheable. + 31 + 1 + + + + + MDMA_C15BNDTR + MDMA_C15BNDTR + MDMA Channel x block number of data + register + 0x414 + 0x20 + read-write + 0x00000000 + + + BNDT + block number of data to + transfer + 0 + 17 + + + BRSUM + Block Repeat Source address Update Mode + These bits are protected and can be written only if + EN is 0. + 18 + 1 + + + BRDUM + Block Repeat Destination address Update + Mode These bits are protected and can be written only + if EN is 0. + 19 + 1 + + + BRC + Block Repeat Count This field contains + the number of repetitions of the current block (0 to + 4095). When the channel is enabled, this register is + read-only, indicating the remaining number of blocks, + excluding the current one. This register decrements + after each complete block transfer. Once the last + block transfer has completed, this register can + either stay at zero or be reloaded automatically from + memory (in Linked List mode - i.e. Link Address + valid). These bits are protected and can be written + only if EN is 0. + 20 + 12 + + + + + MDMA_C15SAR + MDMA_C15SAR + MDMA channel x source address + register + 0x418 + 0x20 + read-write + 0x00000000 + + + SAR + source adr base + 0 + 32 + + + + + MDMA_C15DAR + MDMA_C15DAR + MDMA channel x destination address + register + 0x41C + 0x20 + read-write + 0x00000000 + + + DAR + Destination adr base + 0 + 32 + + + + + MDMA_C15BRUR + MDMA_C15BRUR + MDMA channel x Block Repeat address Update + register + 0x420 + 0x20 + read-write + 0x00000000 + + + SUV + source adresse update + value + 0 + 16 + + + DUV + destination address update + 16 + 16 + + + + + MDMA_C15LAR + MDMA_C15LAR + MDMA channel x Link Address + register + 0x424 + 0x20 + read-write + 0x00000000 + + + LAR + Link address register + 0 + 32 + + + + + MDMA_C15TBR + MDMA_C15TBR + MDMA channel x Trigger and Bus selection + Register + 0x428 + 0x20 + read-write + 0x00000000 + + + TSEL + Trigger selection + 0 + 6 + + + SBUS + Source BUS select This bit is protected + and can be written only if EN is 0. + 16 + 1 + + + DBUS + Destination BUS slect This bit is + protected and can be written only if EN is + 0. + 17 + 1 + + + + + MDMA_C15MAR + MDMA_C15MAR + MDMA channel x Mask address + register + 0x430 + 0x20 + read-write + 0x00000000 + + + MAR + Mask address + 0 + 32 + + + + + MDMA_C15MDR + MDMA_C15MDR + MDMA channel x Mask Data + register + 0x434 + 0x20 + read-write + 0x00000000 + + + MDR + Mask data + 0 + 32 + + + + + + + QUADSPI + QUADSPI + QUADSPI + 0x52005000 + + 0x0 + 0x400 + registers + + + QUADSPI + QuadSPI global interrupt + 92 + + + + CR + CR + QUADSPI control register + 0x0 + 0x20 + read-write + 0x00000000 + + + EN + Enable Enable the QUADSPI. + 0 + 1 + + + ABORT + Abort request This bit aborts the + on-going command sequence. It is automatically reset + once the abort is complete. This bit stops the + current transfer. In polling mode or memory-mapped + mode, this bit also reset the APM bit or the DM + bit. + 1 + 1 + + + DMAEN + DMA enable In indirect mode, DMA can be + used to input or output data via the QUADSPI_DR + register. DMA transfers are initiated when the FIFO + threshold flag, FTF, is set. + 2 + 1 + + + TCEN + Timeout counter enable This bit is valid + only when memory-mapped mode (FMODE = 11) is + selected. Activating this bit causes the chip select + (nCS) to be released (and thus reduces consumption) + if there has not been an access after a certain + amount of time, where this time is defined by + TIMEOUT[15:0] (QUADSPI_LPTR). Enable the timeout + counter. By default, the QUADSPI never stops its + prefetch operation, keeping the previous read + operation active with nCS maintained low, even if no + access to the Flash memory occurs for a long time. + Since Flash memories tend to consume more when nCS is + held low, the application might want to activate the + timeout counter (TCEN = 1, QUADSPI_CR[3]) so that nCS + is released after a period of TIMEOUT[15:0] + (QUADSPI_LPTR) cycles have elapsed without an access + since when the FIFO becomes full with prefetch data. + This bit can be modified only when BUSY = + 0. + 3 + 1 + + + SSHIFT + Sample shift By default, the QUADSPI + samples data 1/2 of a CLK cycle after the data is + driven by the Flash memory. This bit allows the data + is to be sampled later in order to account for + external signal delays. Firmware must assure that + SSHIFT = 0 when in DDR mode (when DDRM = 1). This + field can be modified only when BUSY = + 0. + 4 + 1 + + + DFM + Dual-flash mode This bit activates + dual-flash mode, where two external Flash memories + are used simultaneously to double throughput and + capacity. This bit can be modified only when BUSY = + 0. + 6 + 1 + + + FSEL + Flash memory selection This bit selects + the Flash memory to be addressed in single flash mode + (when DFM = 0). This bit can be modified only when + BUSY = 0. This bit is ignored when DFM = + 1. + 7 + 1 + + + FTHRES + FIFO threshold level Defines, in + indirect mode, the threshold number of bytes in the + FIFO that will cause the FIFO threshold flag (FTF, + QUADSPI_SR[2]) to be set. In indirect write mode + (FMODE = 00): ... In indirect read mode (FMODE = 01): + ... If DMAEN = 1, then the DMA controller for the + corresponding channel must be disabled before + changing the FTHRES value. + 8 + 5 + + + TEIE + Transfer error interrupt enable This bit + enables the transfer error interrupt. + 16 + 1 + + + TCIE + Transfer complete interrupt enable This + bit enables the transfer complete + interrupt. + 17 + 1 + + + FTIE + FIFO threshold interrupt enable This bit + enables the FIFO threshold interrupt. + 18 + 1 + + + SMIE + Status match interrupt enable This bit + enables the status match interrupt. + 19 + 1 + + + TOIE + TimeOut interrupt enable This bit + enables the TimeOut interrupt. + 20 + 1 + + + APMS + Automatic poll mode stop This bit + determines if automatic polling is stopped after a + match. This bit can be modified only when BUSY = + 0. + 22 + 1 + + + PMM + Polling match mode This bit indicates + which method should be used for determining a match + during automatic polling mode. This bit can be + modified only when BUSY = 0. + 23 + 1 + + + PRESCALER + clock prescaler + 24 + 8 + + + + + DCR + DCR + QUADSPI device configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + CKMODE + indicates the level that clk takes + between command + 0 + 1 + + + CSHT + Chip select high time CSHT+1 defines the + minimum number of CLK cycles which the chip select + (nCS) must remain high between commands issued to the + Flash memory. ... This field can be modified only + when BUSY = 0. + 8 + 3 + + + FSIZE + Flash memory size This field defines the + size of external memory using the following formula: + Number of bytes in Flash memory = 2[FSIZE+1] FSIZE+1 + is effectively the number of address bits required to + address the Flash memory. The Flash memory capacity + can be up to 4GB (addressed using 32 bits) in + indirect mode, but the addressable space in + memory-mapped mode is limited to 256MB. If DFM = 1, + FSIZE indicates the total capacity of the two Flash + memories together. This field can be modified only + when BUSY = 0. + 16 + 5 + + + + + SR + SR + QUADSPI status register + 0x8 + 0x20 + read-only + 0x00000000 + + + TEF + Transfer error flag This bit is set in + indirect mode when an invalid address is being + accessed in indirect mode. It is cleared by writing 1 + to CTEF. + 0 + 1 + + + TCF + Transfer complete flag This bit is set + in indirect mode when the programmed number of data + has been transferred or in any mode when the transfer + has been aborted.It is cleared by writing 1 to + CTCF. + 1 + 1 + + + FTF + FIFO threshold flag In indirect mode, + this bit is set when the FIFO threshold has been + reached, or if there is any data left in the FIFO + after reads from the Flash memory are complete. It is + cleared automatically as soon as threshold condition + is no longer true. In automatic polling mode this bit + is set every time the status register is read, and + the bit is cleared when the data register is + read. + 2 + 1 + + + SMF + Status match flag This bit is set in + automatic polling mode when the unmasked received + data matches the corresponding bits in the match + register (QUADSPI_PSMAR). It is cleared by writing 1 + to CSMF. + 3 + 1 + + + TOF + Timeout flag This bit is set when + timeout occurs. It is cleared by writing 1 to + CTOF. + 4 + 1 + + + BUSY + Busy This bit is set when an operation + is on going. This bit clears automatically when the + operation with the Flash memory is finished and the + FIFO is empty. + 5 + 1 + + + FLEVEL + FIFO level This field gives the number + of valid bytes which are being held in the FIFO. + FLEVEL = 0 when the FIFO is empty, and 16 when it is + full. In memory-mapped mode and in automatic status + polling mode, FLEVEL is zero. + 8 + 6 + + + + + FCR + FCR + QUADSPI flag clear register + 0xC + 0x20 + read-write + 0x00000000 + + + CTEF + Clear transfer error flag Writing 1 + clears the TEF flag in the QUADSPI_SR + register + 0 + 1 + + + CTCF + Clear transfer complete flag Writing 1 + clears the TCF flag in the QUADSPI_SR + register + 1 + 1 + + + CSMF + Clear status match flag Writing 1 clears + the SMF flag in the QUADSPI_SR register + 3 + 1 + + + CTOF + Clear timeout flag Writing 1 clears the + TOF flag in the QUADSPI_SR register + 4 + 1 + + + + + DLR + DLR + QUADSPI data length register + 0x10 + 0x20 + read-write + 0x00000000 + + + DL + Data length Number of data to be + retrieved (value+1) in indirect and status-polling + modes. A value no greater than 3 (indicating 4 bytes) + should be used for status-polling mode. All 1s in + indirect mode means undefined length, where QUADSPI + will continue until the end of memory, as defined by + FSIZE. 0x0000_0000: 1 byte is to be transferred + 0x0000_0001: 2 bytes are to be transferred + 0x0000_0002: 3 bytes are to be transferred + 0x0000_0003: 4 bytes are to be transferred ... + 0xFFFF_FFFD: 4,294,967,294 (4G-2) bytes are to be + transferred 0xFFFF_FFFE: 4,294,967,295 (4G-1) bytes + are to be transferred 0xFFFF_FFFF: undefined length + -- all bytes until the end of Flash memory (as + defined by FSIZE) are to be transferred. Continue + reading indefinitely if FSIZE = 0x1F. DL[0] is stuck + at 1 in dual-flash mode (DFM = 1) even when 0 is + written to this bit, thus assuring that each access + transfers an even number of bytes. This field has no + effect when in memory-mapped mode (FMODE = 10). This + field can be written only when BUSY = + 0. + 0 + 32 + + + + + CCR + CCR + QUADSPI communication configuration + register + 0x14 + 0x20 + read-write + 0x00000000 + + + INSTRUCTION + Instruction Instruction to be send to + the external SPI device. This field can be written + only when BUSY = 0. + 0 + 8 + + + IMODE + Instruction mode This field defines the + instruction phase mode of operation: This field can + be written only when BUSY = 0. + 8 + 2 + + + ADMODE + Address mode This field defines the + address phase mode of operation: This field can be + written only when BUSY = 0. + 10 + 2 + + + ADSIZE + Address size This bit defines address + size: This field can be written only when BUSY = + 0. + 12 + 2 + + + ABMODE + Alternate bytes mode This field defines + the alternate-bytes phase mode of operation: This + field can be written only when BUSY = + 0. + 14 + 2 + + + ABSIZE + Alternate bytes size This bit defines + alternate bytes size: This field can be written only + when BUSY = 0. + 16 + 2 + + + DCYC + Number of dummy cycles This field + defines the duration of the dummy phase. In both SDR + and DDR modes, it specifies a number of CLK cycles + (0-31). This field can be written only when BUSY = + 0. + 18 + 5 + + + DMODE + Data mode This field defines the data + phases mode of operation: This field also determines + the dummy phase mode of operation. This field can be + written only when BUSY = 0. + 24 + 2 + + + FMODE + Functional mode This field defines the + QUADSPI functional mode of operation. If DMAEN = 1 + already, then the DMA controller for the + corresponding channel must be disabled before + changing the FMODE value. This field can be written + only when BUSY = 0. + 26 + 2 + + + SIOO + Send instruction only once mode See + Section15.3.11: Sending the instruction only once on + page13. This bit has no effect when IMODE = 00. This + field can be written only when BUSY = + 0. + 28 + 1 + + + DHHC + DDR hold Delay the data output by 1/4 of + the QUADSPI output clock cycle in DDR mode: This + feature is only active in DDR mode. This field can be + written only when BUSY = 0. + 30 + 1 + + + DDRM + Double data rate mode This bit sets the + DDR mode for the address, alternate byte and data + phase: This field can be written only when BUSY = + 0. + 31 + 1 + + + + + AR + AR + QUADSPI address register + 0x18 + 0x20 + read-write + 0x00000000 + + + ADDRESS + [31 0]: Address Address to be send to + the external Flash memory Writes to this field are + ignored when BUSY = 0 or when FMODE = 11 + (memory-mapped mode). In dual flash mode, ADDRESS[0] + is automatically stuck to 0 as the address should + always be even + 0 + 32 + + + + + ABR + ABR + QUADSPI alternate bytes + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + ALTERNATE + Alternate Bytes Optional data to be send + to the external SPI device right after the address. + This field can be written only when BUSY = + 0. + 0 + 32 + + + + + DR + DR + QUADSPI data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data Data to be sent/received to/from + the external SPI device. In indirect write mode, data + written to this register is stored on the FIFO before + it is sent to the Flash memory during the data phase. + If the FIFO is too full, a write operation is stalled + until the FIFO has enough space to accept the amount + of data being written. In indirect read mode, reading + this register gives (via the FIFO) the data which was + received from the Flash memory. If the FIFO does not + have as many bytes as requested by the read operation + and if BUSY=1, the read operation is stalled until + enough data is present or until the transfer is + complete, whichever happens first. In automatic + polling mode, this register contains the last data + read from the Flash memory (without masking). Word, + halfword, and byte accesses to this register are + supported. In indirect write mode, a byte write adds + 1 byte to the FIFO, a halfword write 2, and a word + write 4. Similarly, in indirect read mode, a byte + read removes 1 byte from the FIFO, a halfword read 2, + and a word read 4. Accesses in indirect mode must be + aligned to the bottom of this register: a byte read + must read DATA[7:0] and a halfword read must read + DATA[15:0]. + 0 + 32 + + + + + PSMKR + PSMKR + QUADSPI polling status mask + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MASK + Status mask Mask to be applied to the + status bytes received in polling mode. For bit n: + This field can be written only when BUSY = + 0. + 0 + 32 + + + + + PSMAR + PSMAR + QUADSPI polling status match + register + 0x28 + 0x20 + read-write + 0x00000000 + + + MATCH + Status match Value to be compared with + the masked status register to get a match. This field + can be written only when BUSY = 0. + 0 + 32 + + + + + PIR + PIR + QUADSPI polling interval + register + 0x2C + 0x20 + read-write + 0x00000000 + + + INTERVAL + Polling interval Number of CLK cycles + between to read during automatic polling phases. This + field can be written only when BUSY = + 0. + 0 + 16 + + + + + LPTR + LPTR + QUADSPI low-power timeout + register + 0x30 + 0x20 + read-write + 0x00000000 + + + TIMEOUT + Timeout period After each access in + memory-mapped mode, the QUADSPI prefetches the + subsequent bytes and holds these bytes in the FIFO. + This field indicates how many CLK cycles the QUADSPI + waits after the FIFO becomes full until it raises + nCS, putting the Flash memory in a lower-consumption + state. This field can be written only when BUSY = + 0. + 0 + 16 + + + + + + + RNG + RNG + RNG + 0x48021800 + + 0x0 + 0x400 + registers + + + + CR + CR + RNG control register + 0x0 + 0x20 + read-write + 0x00000000 + + + RNGEN + Random number generator + enable + 2 + 1 + + + IE + Interrupt enable + 3 + 1 + + + CED + Clock error detection Note: The clock + error detection can be used only when ck_rc48 or + ck_pll1_q (ck_pll1_q = 48MHz) source is selected + otherwise, CED bit must be equal to 1. The clock + error detection cannot be enabled nor disabled on the + fly when RNG peripheral is enabled, to enable or + disable CED the RNG must be disabled. + 5 + 1 + + + + + SR + SR + RNG status register + 0x4 + 0x20 + 0x00000000 + + + DRDY + Data ready Note: If IE=1 in RNG_CR, an + interrupt is generated when DRDY=1. It can rise when + the peripheral is disabled. When the output buffer + becomes empty (after reading RNG_DR), this bit + returns to 0 until a new random value is + generated. + 0 + 1 + read-only + + + CECS + Clock error current status Note: This + bit is meaningless if CED (Clock error detection) bit + in RNG_CR is equal to 1. + 1 + 1 + read-only + + + SECS + Seed error current status ** More than + 64 consecutive bits at the same value (0 or 1) ** + More than 32 consecutive alternances of 0 and 1 + (0101010101...01) + 2 + 1 + read-only + + + CEIS + Clock error interrupt status This bit is + set at the same time as CECS. It is cleared by + writing it to 0. An interrupt is pending if IE = 1 in + the RNG_CR register. Note: This bit is meaningless if + CED (Clock error detection) bit in RNG_CR is equal to + 1. + 5 + 1 + read-write + + + SEIS + Seed error interrupt status This bit is + set at the same time as SECS. It is cleared by + writing it to 0. ** More than 64 consecutive bits at + the same value (0 or 1) ** More than 32 consecutive + alternances of 0 and 1 (0101010101...01) An interrupt + is pending if IE = 1 in the RNG_CR + register. + 6 + 1 + read-write + + + + + DR + DR + The RNG_DR register is a read-only register + that delivers a 32-bit random value when read. The + content of this register is valid when DRDY= 1, even if + RNGEN=0. + 0x8 + 0x20 + read-only + 0x00000000 + + + RNDATA + Random data 32-bit random data which are + valid when DRDY=1. + 0 + 32 + + + + + + + RTC + RTC + RTC + 0x58004000 + + 0x0 + 0x400 + registers + + + RTC_TAMP_STAMP_CSS_LSE + RTC tamper, timestamp + 2 + + + RTC_WKUP + RTC Wakeup interrupt + 3 + + + + RTC_TR + RTC_TR + The RTC_TR is the calendar time shadow + register. This register must be written in initialization + mode only. Refer to Calendar initialization and + configuration on page9 and Reading the calendar on + page10.This register is write protected. The write access + procedure is described in RTC register write protection + on page9. + 0x0 + 0x20 + read-write + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + RTC_DR + RTC_DR + The RTC_DR is the calendar date shadow + register. This register must be written in initialization + mode only. Refer to Calendar initialization and + configuration on page9 and Reading the calendar on + page10.This register is write protected. The write access + procedure is described in RTC register write protection + on page9. + 0x4 + 0x20 + read-write + 0x00002101 + + + DU + Date units in BCD format + 0 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + MU + Month units in BCD format + 8 + 4 + + + MT + Month tens in BCD format + 12 + 1 + + + WDU + Week day units + 13 + 3 + + + YU + Year units in BCD format + 16 + 4 + + + YT + Year tens in BCD format + 20 + 4 + + + + + RTC_CR + RTC_CR + RTC control register + 0x8 + 0x20 + 0x00000000 + + + WUCKSEL + Wakeup clock selection + 0 + 3 + read-write + + + TSEDGE + Time-stamp event active edge TSE must be + reset when TSEDGE is changed to avoid unwanted TSF + setting. + 3 + 1 + read-write + + + REFCKON + RTC_REFIN reference clock detection + enable (50 or 60Hz) Note: PREDIV_S must be + 0x00FF. + 4 + 1 + read-write + + + BYPSHAD + Bypass the shadow registers Note: If the + frequency of the APB clock is less than seven times + the frequency of RTCCLK, BYPSHAD must be set to + 1. + 5 + 1 + read-write + + + FMT + Hour format + 6 + 1 + read-write + + + ALRAE + Alarm A enable + 8 + 1 + read-write + + + ALRBE + Alarm B enable + 9 + 1 + read-write + + + WUTE + Wakeup timer enable + 10 + 1 + read-write + + + TSE + timestamp enable + 11 + 1 + read-write + + + ALRAIE + Alarm A interrupt enable + 12 + 1 + read-write + + + ALRBIE + Alarm B interrupt enable + 13 + 1 + read-write + + + WUTIE + Wakeup timer interrupt + enable + 14 + 1 + read-write + + + TSIE + Time-stamp interrupt + enable + 15 + 1 + read-write + + + ADD1H + Add 1 hour (summer time change) When + this bit is set outside initialization mode, 1 hour + is added to the calendar time. This bit is always + read as 0. + 16 + 1 + write-only + + + SUB1H + Subtract 1 hour (winter time change) + When this bit is set outside initialization mode, 1 + hour is subtracted to the calendar time if the + current hour is not 0. This bit is always read as 0. + Setting this bit has no effect when current hour is + 0. + 17 + 1 + write-only + + + BKP + Backup This bit can be written by the + user to memorize whether the daylight saving time + change has been performed or not. + 18 + 1 + read-write + + + COSEL + Calibration output selection When COE=1, + this bit selects which signal is output on RTC_CALIB. + These frequencies are valid for RTCCLK at 32.768 kHz + and prescalers at their default values (PREDIV_A=127 + and PREDIV_S=255). Refer to Section24.3.15: + Calibration clock output + 19 + 1 + read-write + + + POL + Output polarity This bit is used to + configure the polarity of RTC_ALARM + output + 20 + 1 + read-write + + + OSEL + Output selection These bits are used to + select the flag to be routed to RTC_ALARM + output + 21 + 2 + read-write + + + COE + Calibration output enable This bit + enables the RTC_CALIB output + 23 + 1 + read-write + + + ITSE + timestamp on internal event + enable + 24 + 1 + read-write + + + + + RTC_ISR + RTC_ISR + This register is write protected (except for + RTC_ISR[13:8] bits). The write access procedure is + described in RTC register write protection on + page9. + 0xC + 0x20 + 0x00000007 + + + ALRAWF + Alarm A write flag This bit is set by + hardware when Alarm A values can be changed, after + the ALRAE bit has been set to 0 in RTC_CR. It is + cleared by hardware in initialization + mode. + 0 + 1 + read-only + + + ALRBWF + Alarm B write flag This bit is set by + hardware when Alarm B values can be changed, after + the ALRBE bit has been set to 0 in RTC_CR. It is + cleared by hardware in initialization + mode. + 1 + 1 + read-only + + + WUTWF + Wakeup timer write flag This bit is set + by hardware up to 2 RTCCLK cycles after the WUTE bit + has been set to 0 in RTC_CR, and is cleared up to 2 + RTCCLK cycles after the WUTE bit has been set to 1. + The wakeup timer values can be changed when WUTE bit + is cleared and WUTWF is set. + 2 + 1 + read-only + + + SHPF + Shift operation pending This flag is set + by hardware as soon as a shift operation is initiated + by a write to the RTC_SHIFTR register. It is cleared + by hardware when the corresponding shift operation + has been executed. Writing to the SHPF bit has no + effect. + 3 + 1 + read-only + + + INITS + Initialization status flag This bit is + set by hardware when the calendar year field is + different from 0 (Backup domain reset + state). + 4 + 1 + read-only + + + RSF + Registers synchronization flag This bit + is set by hardware each time the calendar registers + are copied into the shadow registers (RTC_SSRx, + RTC_TRx and RTC_DRx). This bit is cleared by hardware + in initialization mode, while a shift operation is + pending (SHPF=1), or when in bypass shadow register + mode (BYPSHAD=1). This bit can also be cleared by + software. It is cleared either by software or by + hardware in initialization mode. + 5 + 1 + read-write + + + INITF + Initialization flag When this bit is set + to 1, the RTC is in initialization state, and the + time, date and prescaler registers can be + updated. + 6 + 1 + read-only + + + INIT + Initialization mode + 7 + 1 + read-write + + + ALRAF + Alarm A flag This flag is set by + hardware when the time/date registers (RTC_TR and + RTC_DR) match the Alarm A register (RTC_ALRMAR). This + flag is cleared by software by writing + 0. + 8 + 1 + read-write + + + ALRBF + Alarm B flag This flag is set by + hardware when the time/date registers (RTC_TR and + RTC_DR) match the Alarm B register (RTC_ALRMBR). This + flag is cleared by software by writing + 0. + 9 + 1 + read-write + + + WUTF + Wakeup timer flag This flag is set by + hardware when the wakeup auto-reload counter reaches + 0. This flag is cleared by software by writing 0. + This flag must be cleared by software at least 1.5 + RTCCLK periods before WUTF is set to 1 + again. + 10 + 1 + read-write + + + TSF + Time-stamp flag This flag is set by + hardware when a time-stamp event occurs. This flag is + cleared by software by writing 0. + 11 + 1 + read-write + + + TSOVF + Time-stamp overflow flag This flag is + set by hardware when a time-stamp event occurs while + TSF is already set. This flag is cleared by software + by writing 0. It is recommended to check and then + clear TSOVF only after clearing the TSF bit. + Otherwise, an overflow might not be noticed if a + time-stamp event occurs immediately before the TSF + bit is cleared. + 12 + 1 + read-write + + + TAMP1F + RTC_TAMP1 detection flag This flag is + set by hardware when a tamper detection event is + detected on the RTC_TAMP1 input. It is cleared by + software writing 0 + 13 + 1 + read-write + + + TAMP2F + RTC_TAMP2 detection flag This flag is + set by hardware when a tamper detection event is + detected on the RTC_TAMP2 input. It is cleared by + software writing 0 + 14 + 1 + read-write + + + TAMP3F + RTC_TAMP3 detection flag This flag is + set by hardware when a tamper detection event is + detected on the RTC_TAMP3 input. It is cleared by + software writing 0 + 15 + 1 + read-write + + + RECALPF + Recalibration pending Flag The RECALPF + status flag is automatically set to 1 when software + writes to the RTC_CALR register, indicating that the + RTC_CALR register is blocked. When the new + calibration settings are taken into account, this bit + returns to 0. Refer to Re-calibration + on-the-fly. + 16 + 1 + read-only + + + ITSF + Internal tTime-stamp flag + 17 + 1 + read-write + + + + + RTC_PRER + RTC_PRER + This register must be written in + initialization mode only. The initialization must be + performed in two separate write accesses. Refer to + Calendar initialization and configuration on page9.This + register is write protected. The write access procedure + is described in RTC register write protection on + page9. + 0x10 + 0x20 + read-write + 0x007F00FF + + + PREDIV_S + Synchronous prescaler factor This is the + synchronous division factor: ck_spre frequency = + ck_apre frequency/(PREDIV_S+1) + 0 + 15 + + + PREDIV_A + Asynchronous prescaler factor This is + the asynchronous division factor: ck_apre frequency = + RTCCLK frequency/(PREDIV_A+1) + 16 + 7 + + + + + RTC_WUTR + RTC_WUTR + This register can be written only when WUTWF + is set to 1 in RTC_ISR.This register is write protected. + The write access procedure is described in RTC register + write protection on page9. + 0x14 + 0x20 + read-write + 0x0000FFFF + + + WUT + Wakeup auto-reload value bits When the + wakeup timer is enabled (WUTE set to 1), the WUTF + flag is set every (WUT[15:0] + 1) ck_wut cycles. The + ck_wut period is selected through WUCKSEL[2:0] bits + of the RTC_CR register When WUCKSEL[2] = 1, the + wakeup timer becomes 17-bits and WUCKSEL[1] + effectively becomes WUT[16] the most-significant bit + to be reloaded into the timer. The first assertion of + WUTF occurs (WUT+1) ck_wut cycles after WUTE is set. + Setting WUT[15:0] to 0x0000 with WUCKSEL[2:0] =011 + (RTCCLK/2) is forbidden. + 0 + 16 + + + + + RTC_ALRMAR + RTC_ALRMAR + This register can be written only when + ALRAWF is set to 1 in RTC_ISR, or in initialization + mode.This register is write protected. The write access + procedure is described in RTC register write protection + on page9. + 0x1C + 0x20 + read-write + 0x00000000 + + + SU + Second units in BCD + format. + 0 + 4 + + + ST + Second tens in BCD format. + 4 + 3 + + + MSK1 + Alarm A seconds mask + 7 + 1 + + + MNU + Minute units in BCD + format. + 8 + 4 + + + MNT + Minute tens in BCD format. + 12 + 3 + + + MSK2 + Alarm A minutes mask + 15 + 1 + + + HU + Hour units in BCD format. + 16 + 4 + + + HT + Hour tens in BCD format. + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + MSK3 + Alarm A hours mask + 23 + 1 + + + DU + Date units or day in BCD + format. + 24 + 4 + + + DT + Date tens in BCD format. + 28 + 2 + + + WDSEL + Week day selection + 30 + 1 + + + MSK4 + Alarm A date mask + 31 + 1 + + + + + RTC_ALRMBR + RTC_ALRMBR + This register can be written only when + ALRBWF is set to 1 in RTC_ISR, or in initialization + mode.This register is write protected. The write access + procedure is described in RTC register write protection + on page9. + 0x20 + 0x20 + read-write + 0x00000000 + + + SU + Second units in BCD format + 0 + 4 + + + ST + Second tens in BCD format + 4 + 3 + + + MSK1 + Alarm B seconds mask + 7 + 1 + + + MNU + Minute units in BCD format + 8 + 4 + + + MNT + Minute tens in BCD format + 12 + 3 + + + MSK2 + Alarm B minutes mask + 15 + 1 + + + HU + Hour units in BCD format + 16 + 4 + + + HT + Hour tens in BCD format + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + MSK3 + Alarm B hours mask + 23 + 1 + + + DU + Date units or day in BCD + format + 24 + 4 + + + DT + Date tens in BCD format + 28 + 2 + + + WDSEL + Week day selection + 30 + 1 + + + MSK4 + Alarm B date mask + 31 + 1 + + + + + RTC_WPR + RTC_WPR + RTC write protection register + 0x24 + 0x20 + write-only + 0x00000000 + + + KEY + Write protection key This byte is + written by software. Reading this byte always returns + 0x00. Refer to RTC register write protection for a + description of how to unlock RTC register write + protection. + 0 + 8 + + + + + RTC_SSR + RTC_SSR + RTC sub second register + 0x28 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value SS[15:0] is the value + in the synchronous prescaler counter. The fraction of + a second is given by the formula below: Second + fraction = (PREDIV_S - SS) / (PREDIV_S + 1) Note: SS + can be larger than PREDIV_S only after a shift + operation. In that case, the correct time/date is one + second less than as indicated by + RTC_TR/RTC_DR. + 0 + 16 + + + + + RTC_SHIFTR + RTC_SHIFTR + This register is write protected. The write + access procedure is described in RTC register write + protection on page9. + 0x2C + 0x20 + write-only + 0x00000000 + + + SUBFS + Subtract a fraction of a second These + bits are write only and is always read as zero. + Writing to this bit has no effect when a shift + operation is pending (when SHPF=1, in RTC_ISR). The + value which is written to SUBFS is added to the + synchronous prescaler counter. Since this counter + counts down, this operation effectively subtracts + from (delays) the clock by: Delay (seconds) = SUBFS / + (PREDIV_S + 1) A fraction of a second can effectively + be added to the clock (advancing the clock) when the + ADD1S function is used in conjunction with SUBFS, + effectively advancing the clock by: Advance (seconds) + = (1 - (SUBFS / (PREDIV_S + 1))). Note: Writing to + SUBFS causes RSF to be cleared. Software can then + wait until RSF=1 to be sure that the shadow registers + have been updated with the shifted + time. + 0 + 15 + + + ADD1S + Add one second This bit is write only + and is always read as zero. Writing to this bit has + no effect when a shift operation is pending (when + SHPF=1, in RTC_ISR). This function is intended to be + used with SUBFS (see description below) in order to + effectively add a fraction of a second to the clock + in an atomic operation. + 31 + 1 + + + + + RTC_TSTR + RTC_TSTR + The content of this register is valid only + when TSF is set to 1 in RTC_ISR. It is cleared when TSF + bit is reset. + 0x30 + 0x20 + read-only + 0x00000000 + + + SU + Second units in BCD + format. + 0 + 4 + + + ST + Second tens in BCD format. + 4 + 3 + + + MNU + Minute units in BCD + format. + 8 + 4 + + + MNT + Minute tens in BCD format. + 12 + 3 + + + HU + Hour units in BCD format. + 16 + 4 + + + HT + Hour tens in BCD format. + 20 + 2 + + + PM + AM/PM notation + 22 + 1 + + + + + RTC_TSDR + RTC_TSDR + The content of this register is valid only + when TSF is set to 1 in RTC_ISR. It is cleared when TSF + bit is reset. + 0x34 + 0x20 + read-only + 0x00000000 + + + DU + Date units in BCD format + 0 + 4 + + + DT + Date tens in BCD format + 4 + 2 + + + MU + Month units in BCD format + 8 + 4 + + + MT + Month tens in BCD format + 12 + 1 + + + WDU + Week day units + 13 + 3 + + + + + RTC_TSSSR + RTC_TSSSR + The content of this register is valid only + when RTC_ISR/TSF is set. It is cleared when the + RTC_ISR/TSF bit is reset. + 0x38 + 0x20 + read-only + 0x00000000 + + + SS + Sub second value SS[15:0] is the value + of the synchronous prescaler counter when the + timestamp event occurred. + 0 + 16 + + + + + RTC_CALR + RTC_CALR + This register is write protected. The write + access procedure is described in RTC register write + protection on page9. + 0x3C + 0x20 + read-write + 0x00000000 + + + CALM + Calibration minus The frequency of the + calendar is reduced by masking CALM out of 220 RTCCLK + pulses (32 seconds if the input frequency is 32768 + Hz). This decreases the frequency of the calendar + with a resolution of 0.9537 ppm. To increase the + frequency of the calendar, this feature should be + used in conjunction with CALP. See Section24.3.12: + RTC smooth digital calibration on + page13. + 0 + 9 + + + CALW16 + Use a 16-second calibration cycle period + When CALW16 is set to 1, the 16-second calibration + cycle period is selected.This bit must not be set to + 1 if CALW8=1. Note: CALM[0] is stuck at 0 when + CALW16= 1. Refer to Section24.3.12: RTC smooth + digital calibration. + 13 + 1 + + + CALW8 + Use an 8-second calibration cycle period + When CALW8 is set to 1, the 8-second calibration + cycle period is selected. Note: CALM[1:0] are stuck + at 00; when CALW8= 1. Refer to Section24.3.12: RTC + smooth digital calibration. + 14 + 1 + + + CALP + Increase frequency of RTC by 488.5 ppm + This feature is intended to be used in conjunction + with CALM, which lowers the frequency of the calendar + with a fine resolution. if the input frequency is + 32768 Hz, the number of RTCCLK pulses added during a + 32-second window is calculated as follows: (512 * + CALP) - CALM. Refer to Section24.3.12: RTC smooth + digital calibration. + 15 + 1 + + + + + RTC_TAMPCR + RTC_TAMPCR + RTC tamper and alternate function + configuration register + 0x40 + 0x20 + read-write + 0x00000000 + + + TAMP1E + RTC_TAMP1 input detection + enable + 0 + 1 + + + TAMP1TRG + Active level for RTC_TAMP1 input If + TAMPFLT != 00 if TAMPFLT = 00: + 1 + 1 + + + TAMPIE + Tamper interrupt enable + 2 + 1 + + + TAMP2E + RTC_TAMP2 input detection + enable + 3 + 1 + + + TAMP2TRG + Active level for RTC_TAMP2 input if + TAMPFLT != 00: if TAMPFLT = 00: + 4 + 1 + + + TAMP3E + RTC_TAMP3 detection enable + 5 + 1 + + + TAMP3TRG + Active level for RTC_TAMP3 input if + TAMPFLT != 00: if TAMPFLT = 00: + 6 + 1 + + + TAMPTS + Activate timestamp on tamper detection + event TAMPTS is valid even if TSE=0 in the RTC_CR + register. + 7 + 1 + + + TAMPFREQ + Tamper sampling frequency Determines the + frequency at which each of the RTC_TAMPx inputs are + sampled. + 8 + 3 + + + TAMPFLT + RTC_TAMPx filter count These bits + determines the number of consecutive samples at the + specified level (TAMP*TRG) needed to activate a + Tamper event. TAMPFLT is valid for each of the + RTC_TAMPx inputs. + 11 + 2 + + + TAMPPRCH + RTC_TAMPx precharge duration These bit + determines the duration of time during which the + pull-up/is activated before each sample. TAMPPRCH is + valid for each of the RTC_TAMPx inputs. + 13 + 2 + + + TAMPPUDIS + RTC_TAMPx pull-up disable This bit + determines if each of the RTC_TAMPx pins are + pre-charged before each sample. + 15 + 1 + + + TAMP1IE + Tamper 1 interrupt enable + 16 + 1 + + + TAMP1NOERASE + Tamper 1 no erase + 17 + 1 + + + TAMP1MF + Tamper 1 mask flag + 18 + 1 + + + TAMP2IE + Tamper 2 interrupt enable + 19 + 1 + + + TAMP2NOERASE + Tamper 2 no erase + 20 + 1 + + + TAMP2MF + Tamper 2 mask flag + 21 + 1 + + + TAMP3IE + Tamper 3 interrupt enable + 22 + 1 + + + TAMP3NOERASE + Tamper 3 no erase + 23 + 1 + + + TAMP3MF + Tamper 3 mask flag + 24 + 1 + + + + + RTC_ALRMASSR + RTC_ALRMASSR + This register can be written only when ALRAE + is reset in RTC_CR register, or in initialization + mode.This register is write protected. The write access + procedure is described in RTC register write protection + on page9 + 0x44 + 0x20 + read-write + 0x00000000 + + + SS + Sub seconds value This value is compared + with the contents of the synchronous prescaler + counter to determine if Alarm A is to be activated. + Only bits 0 up MASKSS-1 are compared. + 0 + 15 + + + MASKSS + Mask the most-significant bits starting + at this bit ... The overflow bits of the synchronous + counter (bits 15) is never compared. This bit can be + different from 0 only after a shift + operation. + 24 + 4 + + + + + RTC_ALRMBSSR + RTC_ALRMBSSR + This register can be written only when ALRBE + is reset in RTC_CR register, or in initialization + mode.This register is write protected.The write access + procedure is described in Section: RTC register write + protection. + 0x48 + 0x20 + read-write + 0x00000000 + + + SS + Sub seconds value This value is compared + with the contents of the synchronous prescaler + counter to determine if Alarm B is to be activated. + Only bits 0 up to MASKSS-1 are + compared. + 0 + 15 + + + MASKSS + Mask the most-significant bits starting + at this bit ... The overflow bits of the synchronous + counter (bits 15) is never compared. This bit can be + different from 0 only after a shift + operation. + 24 + 4 + + + + + RTC_BKP0R + RTC_BKP0R + RTC backup registers + 0x50 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP1R + RTC_BKP1R + RTC backup registers + 0x54 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP2R + RTC_BKP2R + RTC backup registers + 0x58 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP3R + RTC_BKP3R + RTC backup registers + 0x5C + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP4R + RTC_BKP4R + RTC backup registers + 0x60 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP5R + RTC_BKP5R + RTC backup registers + 0x64 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP6R + RTC_BKP6R + RTC backup registers + 0x68 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP7R + RTC_BKP7R + RTC backup registers + 0x6C + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP8R + RTC_BKP8R + RTC backup registers + 0x70 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP9R + RTC_BKP9R + RTC backup registers + 0x74 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP10R + RTC_BKP10R + RTC backup registers + 0x78 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP11R + RTC_BKP11R + RTC backup registers + 0x7C + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP12R + RTC_BKP12R + RTC backup registers + 0x80 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP13R + RTC_BKP13R + RTC backup registers + 0x84 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP14R + RTC_BKP14R + RTC backup registers + 0x88 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP15R + RTC_BKP15R + RTC backup registers + 0x8C + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_OR + RTC_OR + RTC option register + 0x4C + 0x20 + read-write + 0x00000000 + + + RTC_ALARM_TYPE + RTC_ALARM output type on + PC13 + 0 + 1 + + + RTC_OUT_RMP + RTC_OUT remap + 1 + 1 + + + + + RTC_BKP16R + RTC_BKP16R + RTC backup registers + 0x90 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP17R + RTC_BKP17R + RTC backup registers + 0x94 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP18R + RTC_BKP18R + RTC backup registers + 0x98 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP19R + RTC_BKP19R + RTC backup registers + 0x9C + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP20R + RTC_BKP20R + RTC backup registers + 0xA0 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP21R + RTC_BKP21R + RTC backup registers + 0xA4 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP22R + RTC_BKP22R + RTC backup registers + 0xA8 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP23R + RTC_BKP23R + RTC backup registers + 0xAC + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP24R + RTC_BKP24R + RTC backup registers + 0xB0 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP25R + RTC_BKP25R + RTC backup registers + 0xB4 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP26R + RTC_BKP26R + RTC backup registers + 0xB8 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP27R + RTC_BKP27R + RTC backup registers + 0xBC + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP28R + RTC_BKP28R + RTC backup registers + 0xC0 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP29R + RTC_BKP29R + RTC backup registers + 0xC4 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP30R + RTC_BKP30R + RTC backup registers + 0xC8 + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + RTC_BKP31R + RTC_BKP31R + RTC backup registers + 0xCC + 0x20 + read-write + 0x00000000 + + + BKP + The application can write or read data + to and from these registers. They are powered-on by + VBAT when VDD is switched off, so that they are not + reset by System reset, and their contents remain + valid when the device operates in low-power mode. + This register is reset on a tamper detection event, + as long as TAMPxF=1. or when the Flash readout + protection is disabled. + 0 + 32 + + + + + + + SAI4 + SAI + SAI + 0x58005400 + + 0x0 + 0x400 + registers + + + SAI4 + SAI4 global interrupt + 146 + + + + SAI_GCR + SAI_GCR + Global configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + SYNCOUT + Synchronization outputs These bits are + set and cleared by software. + 4 + 2 + + + SYNCIN + Synchronization inputs + 0 + 2 + + + + + SAI_ACR1 + SAI_ACR1 + Configuration register 1 + 0x4 + 0x20 + read-write + 0x00000040 + + + MODE + SAIx audio block mode + immediately + 0 + 2 + + + PRTCFG + Protocol configuration. These bits are + set and cleared by software. These bits have to be + configured when the audio block is + disabled. + 2 + 2 + + + DS + Data size. These bits are set and + cleared by software. These bits are ignored when the + SPDIF protocols are selected (bit PRTCFG[1:0]), + because the frame and the data size are fixed in such + case. When the companding mode is selected through + COMP[1:0] bits, DS[1:0] are ignored since the data + size is fixed to 8 bits by the algorithm. These bits + must be configured when the audio block is + disabled. + 5 + 3 + + + LSBFIRST + Least significant bit first. This bit is + set and cleared by software. It must be configured + when the audio block is disabled. This bit has no + meaning in AC97 audio protocol since AC97 data are + always transferred with the MSB first. This bit has + no meaning in SPDIF audio protocol since in SPDIF + data are always transferred with LSB + first. + 8 + 1 + + + CKSTR + Clock strobing edge. This bit is set and + cleared by software. It must be configured when the + audio block is disabled. This bit has no meaning in + SPDIF audio protocol. + 9 + 1 + + + SYNCEN + Synchronization enable. These bits are + set and cleared by software. They must be configured + when the audio sub-block is disabled. Note: The audio + sub-block should be configured as asynchronous when + SPDIF mode is enabled. + 10 + 2 + + + MONO + Mono mode. This bit is set and cleared + by software. It is meaningful only when the number of + slots is equal to 2. When the mono mode is selected, + slot 0 data are duplicated on slot 1 when the audio + block operates as a transmitter. In reception mode, + the slot1 is discarded and only the data received + from slot 0 are stored. Refer to Section: Mono/stereo + mode for more details. + 12 + 1 + + + OUTDRIV + Output drive. This bit is set and + cleared by software. Note: This bit has to be set + before enabling the audio block and after the audio + block configuration. + 13 + 1 + + + SAIXEN + Audio block enable where x is A or B. + This bit is set by software. To switch off the audio + block, the application software must program this bit + to 0 and poll the bit till it reads back 0, meaning + that the block is completely disabled. Before setting + this bit to 1, check that it is set to 0, otherwise + the enable command will not be taken into account. + This bit allows to control the state of SAIx audio + block. If it is disabled when an audio frame transfer + is ongoing, the ongoing transfer completes and the + cell is fully disabled at the end of this audio frame + transfer. Note: When SAIx block is configured in + master mode, the clock must be present on the input + of SAIx before setting SAIXEN bit. + 16 + 1 + + + DMAEN + DMA enable. This bit is set and cleared + by software. Note: Since the audio block defaults to + operate as a transmitter after reset, the MODE[1:0] + bits must be configured before setting DMAEN to avoid + a DMA request in receiver mode. + 17 + 1 + + + NOMCK + No divider + 19 + 1 + + + MCKDIV + Master clock divider. These bits are set + and cleared by software. These bits are meaningless + when the audio block operates in slave mode. They + have to be configured when the audio block is + disabled. Others: the master clock frequency is + calculated accordingly to the following + formula: + 20 + 4 + + + OSR + Oversampling ratio for master + clock + 26 + 1 + + + + + SAI_ACR2 + SAI_ACR2 + Configuration register 2 + 0x8 + 0x20 + 0x00000000 + + + FTH + FIFO threshold. This bit is set and + cleared by software. + 0 + 3 + read-write + + + FFLUSH + FIFO flush. This bit is set by software. + It is always read as 0. This bit should be configured + when the SAI is disabled. + 3 + 1 + write-only + + + TRIS + Tristate management on data line. This + bit is set and cleared by software. It is meaningful + only if the audio block is configured as a + transmitter. This bit is not used when the audio + block is configured in SPDIF mode. It should be + configured when SAI is disabled. Refer to Section: + Output data line management on an inactive slot for + more details. + 4 + 1 + read-write + + + MUTE + Mute. This bit is set and cleared by + software. It is meaningful only when the audio block + operates as a transmitter. The MUTE value is linked + to value of MUTEVAL if the number of slots is lower + or equal to 2, or equal to 0 if it is greater than 2. + Refer to Section: Mute mode for more details. Note: + This bit is meaningless and should not be used for + SPDIF audio blocks. + 5 + 1 + read-write + + + MUTEVAL + Mute value. This bit is set and cleared + by software.It must be written before enabling the + audio block: SAIXEN. This bit is meaningful only when + the audio block operates as a transmitter, the number + of slots is lower or equal to 2 and the MUTE bit is + set. If more slots are declared, the bit value sent + during the transmission in mute mode is equal to 0, + whatever the value of MUTEVAL. if the number of slot + is lower or equal to 2 and MUTEVAL = 1, the MUTE + value transmitted for each slot is the one sent + during the previous frame. Refer to Section: Mute + mode for more details. Note: This bit is meaningless + and should not be used for SPDIF audio + blocks. + 6 + 1 + read-write + + + MUTECNT + Mute counter. These bits are set and + cleared by software. They are used only in reception + mode. The value set in these bits is compared to the + number of consecutive mute frames detected in + reception. When the number of mute frames is equal to + this value, the flag MUTEDET will be set and an + interrupt will be generated if bit MUTEDETIE is set. + Refer to Section: Mute mode for more + details. + 7 + 6 + read-write + + + CPL + Complement bit. This bit is set and + cleared by software. It defines the type of + complement to be used for companding mode Note: This + bit has effect only when the companding mode is -Law + algorithm or A-Law algorithm. + 13 + 1 + read-write + + + COMP + Companding mode. These bits are set and + cleared by software. The -Law and the A-Law log are a + part of the CCITT G.711 recommendation, the type of + complement that will be used depends on CPL bit. The + data expansion or data compression are determined by + the state of bit MODE[0]. The data compression is + applied if the audio block is configured as a + transmitter. The data expansion is automatically + applied when the audio block is configured as a + receiver. Refer to Section: Companding mode for more + details. Note: Companding mode is applicable only + when TDM is selected. + 14 + 2 + read-write + + + + + SAI_AFRCR + SAI_AFRCR + This register has no meaning in AC97 and + SPDIF audio protocol + 0xC + 0x20 + 0x00000007 + + + FRL + Frame length. These bits are set and + cleared by software. They define the audio frame + length expressed in number of SCK clock cycles: the + number of bits in the frame is equal to FRL[7:0] + 1. + The minimum number of bits to transfer in an audio + frame must be equal to 8, otherwise the audio block + will behaves in an unexpected way. This is the case + when the data size is 8 bits and only one slot 0 is + defined in NBSLOT[4:0] of SAI_xSLOTR register + (NBSLOT[3:0] = 0000). In master mode, if the master + clock (available on MCLK_x pin) is used, the frame + length should be aligned with a number equal to a + power of 2, ranging from 8 to 256. When the master + clock is not used (NODIV = 1), it is recommended to + program the frame length to an value ranging from 8 + to 256. These bits are meaningless and are not used + in AC97 or SPDIF audio block + configuration. + 0 + 8 + read-write + + + FSALL + Frame synchronization active level + length. These bits are set and cleared by software. + They specify the length in number of bit clock (SCK) + + 1 (FSALL[6:0] + 1) of the active level of the FS + signal in the audio frame These bits are meaningless + and are not used in AC97 or SPDIF audio block + configuration. They must be configured when the audio + block is disabled. + 8 + 7 + read-write + + + FSDEF + Frame synchronization definition. This + bit is set and cleared by software. When the bit is + set, the number of slots defined in the SAI_xSLOTR + register has to be even. It means that half of this + number of slots will be dedicated to the left channel + and the other slots for the right channel (e.g: this + bit has to be set for I2S or MSB/LSB-justified + protocols...). This bit is meaningless and is not + used in AC97 or SPDIF audio block configuration. It + must be configured when the audio block is + disabled. + 16 + 1 + read-only + + + FSPOL + Frame synchronization polarity. This bit + is set and cleared by software. It is used to + configure the level of the start of frame on the FS + signal. It is meaningless and is not used in AC97 or + SPDIF audio block configuration. This bit must be + configured when the audio block is + disabled. + 17 + 1 + read-write + + + FSOFF + Frame synchronization offset. This bit + is set and cleared by software. It is meaningless and + is not used in AC97 or SPDIF audio block + configuration. This bit must be configured when the + audio block is disabled. + 18 + 1 + read-write + + + + + SAI_ASLOTR + SAI_ASLOTR + This register has no meaning in AC97 and + SPDIF audio protocol + 0x10 + 0x20 + read-write + 0x00000000 + + + FBOFF + First bit offset These bits are set and + cleared by software. The value set in this bitfield + defines the position of the first data transfer bit + in the slot. It represents an offset value. In + transmission mode, the bits outside the data field + are forced to 0. In reception mode, the extra + received bits are discarded. These bits must be set + when the audio block is disabled. They are ignored in + AC97 or SPDIF mode. + 0 + 5 + + + SLOTSZ + Slot size This bits is set and cleared + by software. The slot size must be higher or equal to + the data size. If this condition is not respected, + the behavior of the SAI will be undetermined. Refer + to Section: Output data line management on an + inactive slot for information on how to drive SD + line. These bits must be set when the audio block is + disabled. They are ignored in AC97 or SPDIF + mode. + 6 + 2 + + + NBSLOT + Number of slots in an audio frame. These + bits are set and cleared by software. The value set + in this bitfield represents the number of slots + 1 + in the audio frame (including the number of inactive + slots). The maximum number of slots is 16. The number + of slots should be even if FSDEF bit in the SAI_xFRCR + register is set. The number of slots must be + configured when the audio block is disabled. They are + ignored in AC97 or SPDIF mode. + 8 + 4 + + + SLOTEN + Slot enable. These bits are set and + cleared by software. Each SLOTEN bit corresponds to a + slot position from 0 to 15 (maximum 16 slots). The + slot must be enabled when the audio block is + disabled. They are ignored in AC97 or SPDIF + mode. + 16 + 16 + + + + + SAI_AIM + SAI_AIM + Interrupt mask register 2 + 0x14 + 0x20 + read-write + 0x00000000 + + + OVRUDRIE + Overrun/underrun interrupt enable. This + bit is set and cleared by software. When this bit is + set, an interrupt is generated if the OVRUDR bit in + the SAI_xSR register is set. + 0 + 1 + + + MUTEDETIE + Mute detection interrupt enable. This + bit is set and cleared by software. When this bit is + set, an interrupt is generated if the MUTEDET bit in + the SAI_xSR register is set. This bit has a meaning + only if the audio block is configured in receiver + mode. + 1 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable. This bit is set and cleared by software. This + bit is taken into account only if the audio block is + configured as a master (MODE[1] = 0) and NODIV = 0. + It generates an interrupt if the WCKCFG flag in the + SAI_xSR register is set. Note: This bit is used only + in TDM mode and is meaningless in other + modes. + 2 + 1 + + + FREQIE + FIFO request interrupt enable. This bit + is set and cleared by software. When this bit is set, + an interrupt is generated if the FREQ bit in the + SAI_xSR register is set. Since the audio block + defaults to operate as a transmitter after reset, the + MODE bit must be configured before setting FREQIE to + avoid a parasitic interruption in receiver + mode, + 3 + 1 + + + CNRDYIE + Codec not ready interrupt enable (AC97). + This bit is set and cleared by software. When the + interrupt is enabled, the audio block detects in the + slot 0 (tag0) of the AC97 frame if the Codec + connected to this line is ready or not. If it is not + ready, the CNRDY flag in the SAI_xSR register is set + and an interruption i generated. This bit has a + meaning only if the AC97 mode is selected through + PRTCFG[1:0] bits and the audio block is operates as a + receiver. + 4 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable. This bit is set and + cleared by software. When this bit is set, an + interrupt will be generated if the AFSDET bit in the + SAI_xSR register is set. This bit is meaningless in + AC97, SPDIF mode or when the audio block operates as + a master. + 5 + 1 + + + LFSDETIE + Late frame synchronization detection + interrupt enable. This bit is set and cleared by + software. When this bit is set, an interrupt will be + generated if the LFSDET bit is set in the SAI_xSR + register. This bit is meaningless in AC97, SPDIF mode + or when the audio block operates as a + master. + 6 + 1 + + + + + SAI_ASR + SAI_ASR + Status register + 0x18 + 0x20 + read-only + 0x00000008 + + + OVRUDR + Overrun / underrun. This bit is read + only. The overrun and underrun conditions can occur + only when the audio block is configured as a receiver + and a transmitter, respectively. It can generate an + interrupt if OVRUDRIE bit is set in SAI_xIM register. + This flag is cleared when the software sets COVRUDR + bit in SAI_xCLRFR register. + 0 + 1 + + + MUTEDET + Mute detection. This bit is read only. + This flag is set if consecutive 0 values are received + in each slot of a given audio frame and for a + consecutive number of audio frames (set in the + MUTECNT bit in the SAI_xCR2 register). It can + generate an interrupt if MUTEDETIE bit is set in + SAI_xIM register. This flag is cleared when the + software sets bit CMUTEDET in the SAI_xCLRFR + register. + 1 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. This bit is used only when the audio + block operates in master mode (MODE[1] = 0) and NODIV + = 0. It can generate an interrupt if WCKCFGIE bit is + set in SAI_xIM register. This flag is cleared when + the software sets CWCKCFG bit in SAI_xCLRFR + register. + 2 + 1 + + + FREQ + FIFO request. This bit is read only. The + request depends on the audio block configuration: If + the block is configured in transmission mode, the + FIFO request is related to a write request operation + in the SAI_xDR. If the block configured in reception, + the FIFO request related to a read request operation + from the SAI_xDR. This flag can generate an interrupt + if FREQIE bit is set in SAI_xIM + register. + 3 + 1 + + + CNRDY + Codec not ready. This bit is read only. + This bit is used only when the AC97 audio protocol is + selected in the SAI_xCR1 register and configured in + receiver mode. It can generate an interrupt if + CNRDYIE bit is set in SAI_xIM register. This flag is + cleared when the software sets CCNRDY bit in + SAI_xCLRFR register. + 4 + 1 + + + AFSDET + Anticipated frame synchronization + detection. This bit is read only. This flag can be + set only if the audio block is configured in slave + mode. It is not used in AC97or SPDIF mode. It can + generate an interrupt if AFSDETIE bit is set in + SAI_xIM register. This flag is cleared when the + software sets CAFSDET bit in SAI_xCLRFR + register. + 5 + 1 + + + LFSDET + Late frame synchronization detection. + This bit is read only. This flag can be set only if + the audio block is configured in slave mode. It is + not used in AC97 or SPDIF mode. It can generate an + interrupt if LFSDETIE bit is set in the SAI_xIM + register. This flag is cleared when the software sets + bit CLFSDET in SAI_xCLRFR register + 6 + 1 + + + FLVL + FIFO level threshold. This bit is read + only. The FIFO level threshold flag is managed only + by hardware and its setting depends on SAI block + configuration (transmitter or receiver mode). If the + SAI block is configured as transmitter: If SAI block + is configured as receiver: + 16 + 3 + + + + + SAI_ACLRFR + SAI_ACLRFR + Clear flag register + 0x1C + 0x20 + write-only + 0x00000000 + + + COVRUDR + Clear overrun / underrun. This bit is + write only. Programming this bit to 1 clears the + OVRUDR flag in the SAI_xSR register. Reading this bit + always returns the value 0. + 0 + 1 + + + CMUTEDET + Mute detection flag. This bit is write + only. Programming this bit to 1 clears the MUTEDET + flag in the SAI_xSR register. Reading this bit always + returns the value 0. + 1 + 1 + + + CWCKCFG + Clear wrong clock configuration flag. + This bit is write only. Programming this bit to 1 + clears the WCKCFG flag in the SAI_xSR register. This + bit is used only when the audio block is set as + master (MODE[1] = 0) and NODIV = 0 in the SAI_xCR1 + register. Reading this bit always returns the value + 0. + 2 + 1 + + + CCNRDY + Clear Codec not ready flag. This bit is + write only. Programming this bit to 1 clears the + CNRDY flag in the SAI_xSR register. This bit is used + only when the AC97 audio protocol is selected in the + SAI_xCR1 register. Reading this bit always returns + the value 0. + 4 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. This bit is write only. Programming + this bit to 1 clears the AFSDET flag in the SAI_xSR + register. It is not used in AC97or SPDIF mode. + Reading this bit always returns the value + 0. + 5 + 1 + + + CLFSDET + Clear late frame synchronization + detection flag. This bit is write only. Programming + this bit to 1 clears the LFSDET flag in the SAI_xSR + register. This bit is not used in AC97or SPDIF mode + Reading this bit always returns the value + 0. + 6 + 1 + + + + + SAI_ADR + SAI_ADR + Data register + 0x20 + 0x20 + read-write + 0x00000000 + + + DATA + Data A write to this register loads the + FIFO provided the FIFO is not full. A read from this + register empties the FIFO if the FIFO is not + empty. + 0 + 32 + + + + + SAI_BCR1 + SAI_BCR1 + Configuration register 1 + 0x24 + 0x20 + read-write + 0x00000040 + + + MODE + SAIx audio block mode + immediately + 0 + 2 + + + PRTCFG + Protocol configuration. These bits are + set and cleared by software. These bits have to be + configured when the audio block is + disabled. + 2 + 2 + + + DS + Data size. These bits are set and + cleared by software. These bits are ignored when the + SPDIF protocols are selected (bit PRTCFG[1:0]), + because the frame and the data size are fixed in such + case. When the companding mode is selected through + COMP[1:0] bits, DS[1:0] are ignored since the data + size is fixed to 8 bits by the algorithm. These bits + must be configured when the audio block is + disabled. + 5 + 3 + + + LSBFIRST + Least significant bit first. This bit is + set and cleared by software. It must be configured + when the audio block is disabled. This bit has no + meaning in AC97 audio protocol since AC97 data are + always transferred with the MSB first. This bit has + no meaning in SPDIF audio protocol since in SPDIF + data are always transferred with LSB + first. + 8 + 1 + + + CKSTR + Clock strobing edge. This bit is set and + cleared by software. It must be configured when the + audio block is disabled. This bit has no meaning in + SPDIF audio protocol. + 9 + 1 + + + SYNCEN + Synchronization enable. These bits are + set and cleared by software. They must be configured + when the audio sub-block is disabled. Note: The audio + sub-block should be configured as asynchronous when + SPDIF mode is enabled. + 10 + 2 + + + MONO + Mono mode. This bit is set and cleared + by software. It is meaningful only when the number of + slots is equal to 2. When the mono mode is selected, + slot 0 data are duplicated on slot 1 when the audio + block operates as a transmitter. In reception mode, + the slot1 is discarded and only the data received + from slot 0 are stored. Refer to Section: Mono/stereo + mode for more details. + 12 + 1 + + + OUTDRIV + Output drive. This bit is set and + cleared by software. Note: This bit has to be set + before enabling the audio block and after the audio + block configuration. + 13 + 1 + + + SAIXEN + Audio block enable where x is A or B. + This bit is set by software. To switch off the audio + block, the application software must program this bit + to 0 and poll the bit till it reads back 0, meaning + that the block is completely disabled. Before setting + this bit to 1, check that it is set to 0, otherwise + the enable command will not be taken into account. + This bit allows to control the state of SAIx audio + block. If it is disabled when an audio frame transfer + is ongoing, the ongoing transfer completes and the + cell is fully disabled at the end of this audio frame + transfer. Note: When SAIx block is configured in + master mode, the clock must be present on the input + of SAIx before setting SAIXEN bit. + 16 + 1 + + + DMAEN + DMA enable. This bit is set and cleared + by software. Note: Since the audio block defaults to + operate as a transmitter after reset, the MODE[1:0] + bits must be configured before setting DMAEN to avoid + a DMA request in receiver mode. + 17 + 1 + + + NOMCK + No divider + 19 + 1 + + + MCKDIV + Master clock divider. These bits are set + and cleared by software. These bits are meaningless + when the audio block operates in slave mode. They + have to be configured when the audio block is + disabled. Others: the master clock frequency is + calculated accordingly to the following + formula: + 20 + 4 + + + OSR + Oversampling ratio for master + clock + 26 + 1 + + + + + SAI_BCR2 + SAI_BCR2 + Configuration register 2 + 0x28 + 0x20 + 0x00000000 + + + FTH + FIFO threshold. This bit is set and + cleared by software. + 0 + 3 + read-write + + + FFLUSH + FIFO flush. This bit is set by software. + It is always read as 0. This bit should be configured + when the SAI is disabled. + 3 + 1 + write-only + + + TRIS + Tristate management on data line. This + bit is set and cleared by software. It is meaningful + only if the audio block is configured as a + transmitter. This bit is not used when the audio + block is configured in SPDIF mode. It should be + configured when SAI is disabled. Refer to Section: + Output data line management on an inactive slot for + more details. + 4 + 1 + read-write + + + MUTE + Mute. This bit is set and cleared by + software. It is meaningful only when the audio block + operates as a transmitter. The MUTE value is linked + to value of MUTEVAL if the number of slots is lower + or equal to 2, or equal to 0 if it is greater than 2. + Refer to Section: Mute mode for more details. Note: + This bit is meaningless and should not be used for + SPDIF audio blocks. + 5 + 1 + read-write + + + MUTEVAL + Mute value. This bit is set and cleared + by software.It must be written before enabling the + audio block: SAIXEN. This bit is meaningful only when + the audio block operates as a transmitter, the number + of slots is lower or equal to 2 and the MUTE bit is + set. If more slots are declared, the bit value sent + during the transmission in mute mode is equal to 0, + whatever the value of MUTEVAL. if the number of slot + is lower or equal to 2 and MUTEVAL = 1, the MUTE + value transmitted for each slot is the one sent + during the previous frame. Refer to Section: Mute + mode for more details. Note: This bit is meaningless + and should not be used for SPDIF audio + blocks. + 6 + 1 + read-write + + + MUTECNT + Mute counter. These bits are set and + cleared by software. They are used only in reception + mode. The value set in these bits is compared to the + number of consecutive mute frames detected in + reception. When the number of mute frames is equal to + this value, the flag MUTEDET will be set and an + interrupt will be generated if bit MUTEDETIE is set. + Refer to Section: Mute mode for more + details. + 7 + 6 + read-write + + + CPL + Complement bit. This bit is set and + cleared by software. It defines the type of + complement to be used for companding mode Note: This + bit has effect only when the companding mode is -Law + algorithm or A-Law algorithm. + 13 + 1 + read-write + + + COMP + Companding mode. These bits are set and + cleared by software. The -Law and the A-Law log are a + part of the CCITT G.711 recommendation, the type of + complement that will be used depends on CPL bit. The + data expansion or data compression are determined by + the state of bit MODE[0]. The data compression is + applied if the audio block is configured as a + transmitter. The data expansion is automatically + applied when the audio block is configured as a + receiver. Refer to Section: Companding mode for more + details. Note: Companding mode is applicable only + when TDM is selected. + 14 + 2 + read-write + + + + + SAI_BFRCR + SAI_BFRCR + This register has no meaning in AC97 and + SPDIF audio protocol + 0x2C + 0x20 + 0x00000007 + + + FRL + Frame length. These bits are set and + cleared by software. They define the audio frame + length expressed in number of SCK clock cycles: the + number of bits in the frame is equal to FRL[7:0] + 1. + The minimum number of bits to transfer in an audio + frame must be equal to 8, otherwise the audio block + will behaves in an unexpected way. This is the case + when the data size is 8 bits and only one slot 0 is + defined in NBSLOT[4:0] of SAI_xSLOTR register + (NBSLOT[3:0] = 0000). In master mode, if the master + clock (available on MCLK_x pin) is used, the frame + length should be aligned with a number equal to a + power of 2, ranging from 8 to 256. When the master + clock is not used (NODIV = 1), it is recommended to + program the frame length to an value ranging from 8 + to 256. These bits are meaningless and are not used + in AC97 or SPDIF audio block + configuration. + 0 + 8 + read-write + + + FSALL + Frame synchronization active level + length. These bits are set and cleared by software. + They specify the length in number of bit clock (SCK) + + 1 (FSALL[6:0] + 1) of the active level of the FS + signal in the audio frame These bits are meaningless + and are not used in AC97 or SPDIF audio block + configuration. They must be configured when the audio + block is disabled. + 8 + 7 + read-write + + + FSDEF + Frame synchronization definition. This + bit is set and cleared by software. When the bit is + set, the number of slots defined in the SAI_xSLOTR + register has to be even. It means that half of this + number of slots will be dedicated to the left channel + and the other slots for the right channel (e.g: this + bit has to be set for I2S or MSB/LSB-justified + protocols...). This bit is meaningless and is not + used in AC97 or SPDIF audio block configuration. It + must be configured when the audio block is + disabled. + 16 + 1 + read-only + + + FSPOL + Frame synchronization polarity. This bit + is set and cleared by software. It is used to + configure the level of the start of frame on the FS + signal. It is meaningless and is not used in AC97 or + SPDIF audio block configuration. This bit must be + configured when the audio block is + disabled. + 17 + 1 + read-write + + + FSOFF + Frame synchronization offset. This bit + is set and cleared by software. It is meaningless and + is not used in AC97 or SPDIF audio block + configuration. This bit must be configured when the + audio block is disabled. + 18 + 1 + read-write + + + + + SAI_BSLOTR + SAI_BSLOTR + This register has no meaning in AC97 and + SPDIF audio protocol + 0x30 + 0x20 + read-write + 0x00000000 + + + FBOFF + First bit offset These bits are set and + cleared by software. The value set in this bitfield + defines the position of the first data transfer bit + in the slot. It represents an offset value. In + transmission mode, the bits outside the data field + are forced to 0. In reception mode, the extra + received bits are discarded. These bits must be set + when the audio block is disabled. They are ignored in + AC97 or SPDIF mode. + 0 + 5 + + + SLOTSZ + Slot size This bits is set and cleared + by software. The slot size must be higher or equal to + the data size. If this condition is not respected, + the behavior of the SAI will be undetermined. Refer + to Section: Output data line management on an + inactive slot for information on how to drive SD + line. These bits must be set when the audio block is + disabled. They are ignored in AC97 or SPDIF + mode. + 6 + 2 + + + NBSLOT + Number of slots in an audio frame. These + bits are set and cleared by software. The value set + in this bitfield represents the number of slots + 1 + in the audio frame (including the number of inactive + slots). The maximum number of slots is 16. The number + of slots should be even if FSDEF bit in the SAI_xFRCR + register is set. The number of slots must be + configured when the audio block is disabled. They are + ignored in AC97 or SPDIF mode. + 8 + 4 + + + SLOTEN + Slot enable. These bits are set and + cleared by software. Each SLOTEN bit corresponds to a + slot position from 0 to 15 (maximum 16 slots). The + slot must be enabled when the audio block is + disabled. They are ignored in AC97 or SPDIF + mode. + 16 + 16 + + + + + SAI_BIM + SAI_BIM + Interrupt mask register 2 + 0x34 + 0x20 + read-write + 0x00000000 + + + OVRUDRIE + Overrun/underrun interrupt enable. This + bit is set and cleared by software. When this bit is + set, an interrupt is generated if the OVRUDR bit in + the SAI_xSR register is set. + 0 + 1 + + + MUTEDETIE + Mute detection interrupt enable. This + bit is set and cleared by software. When this bit is + set, an interrupt is generated if the MUTEDET bit in + the SAI_xSR register is set. This bit has a meaning + only if the audio block is configured in receiver + mode. + 1 + 1 + + + WCKCFGIE + Wrong clock configuration interrupt + enable. This bit is set and cleared by software. This + bit is taken into account only if the audio block is + configured as a master (MODE[1] = 0) and NODIV = 0. + It generates an interrupt if the WCKCFG flag in the + SAI_xSR register is set. Note: This bit is used only + in TDM mode and is meaningless in other + modes. + 2 + 1 + + + FREQIE + FIFO request interrupt enable. This bit + is set and cleared by software. When this bit is set, + an interrupt is generated if the FREQ bit in the + SAI_xSR register is set. Since the audio block + defaults to operate as a transmitter after reset, the + MODE bit must be configured before setting FREQIE to + avoid a parasitic interruption in receiver + mode, + 3 + 1 + + + CNRDYIE + Codec not ready interrupt enable (AC97). + This bit is set and cleared by software. When the + interrupt is enabled, the audio block detects in the + slot 0 (tag0) of the AC97 frame if the Codec + connected to this line is ready or not. If it is not + ready, the CNRDY flag in the SAI_xSR register is set + and an interruption i generated. This bit has a + meaning only if the AC97 mode is selected through + PRTCFG[1:0] bits and the audio block is operates as a + receiver. + 4 + 1 + + + AFSDETIE + Anticipated frame synchronization + detection interrupt enable. This bit is set and + cleared by software. When this bit is set, an + interrupt will be generated if the AFSDET bit in the + SAI_xSR register is set. This bit is meaningless in + AC97, SPDIF mode or when the audio block operates as + a master. + 5 + 1 + + + LFSDETIE + Late frame synchronization detection + interrupt enable. This bit is set and cleared by + software. When this bit is set, an interrupt will be + generated if the LFSDET bit is set in the SAI_xSR + register. This bit is meaningless in AC97, SPDIF mode + or when the audio block operates as a + master. + 6 + 1 + + + + + SAI_BSR + SAI_BSR + Status register + 0x38 + 0x20 + read-only + 0x00000008 + + + OVRUDR + Overrun / underrun. This bit is read + only. The overrun and underrun conditions can occur + only when the audio block is configured as a receiver + and a transmitter, respectively. It can generate an + interrupt if OVRUDRIE bit is set in SAI_xIM register. + This flag is cleared when the software sets COVRUDR + bit in SAI_xCLRFR register. + 0 + 1 + + + MUTEDET + Mute detection. This bit is read only. + This flag is set if consecutive 0 values are received + in each slot of a given audio frame and for a + consecutive number of audio frames (set in the + MUTECNT bit in the SAI_xCR2 register). It can + generate an interrupt if MUTEDETIE bit is set in + SAI_xIM register. This flag is cleared when the + software sets bit CMUTEDET in the SAI_xCLRFR + register. + 1 + 1 + + + WCKCFG + Wrong clock configuration flag. This bit + is read only. This bit is used only when the audio + block operates in master mode (MODE[1] = 0) and NODIV + = 0. It can generate an interrupt if WCKCFGIE bit is + set in SAI_xIM register. This flag is cleared when + the software sets CWCKCFG bit in SAI_xCLRFR + register. + 2 + 1 + + + FREQ + FIFO request. This bit is read only. The + request depends on the audio block configuration: If + the block is configured in transmission mode, the + FIFO request is related to a write request operation + in the SAI_xDR. If the block configured in reception, + the FIFO request related to a read request operation + from the SAI_xDR. This flag can generate an interrupt + if FREQIE bit is set in SAI_xIM + register. + 3 + 1 + + + CNRDY + Codec not ready. This bit is read only. + This bit is used only when the AC97 audio protocol is + selected in the SAI_xCR1 register and configured in + receiver mode. It can generate an interrupt if + CNRDYIE bit is set in SAI_xIM register. This flag is + cleared when the software sets CCNRDY bit in + SAI_xCLRFR register. + 4 + 1 + + + AFSDET + Anticipated frame synchronization + detection. This bit is read only. This flag can be + set only if the audio block is configured in slave + mode. It is not used in AC97or SPDIF mode. It can + generate an interrupt if AFSDETIE bit is set in + SAI_xIM register. This flag is cleared when the + software sets CAFSDET bit in SAI_xCLRFR + register. + 5 + 1 + + + LFSDET + Late frame synchronization detection. + This bit is read only. This flag can be set only if + the audio block is configured in slave mode. It is + not used in AC97 or SPDIF mode. It can generate an + interrupt if LFSDETIE bit is set in the SAI_xIM + register. This flag is cleared when the software sets + bit CLFSDET in SAI_xCLRFR register + 6 + 1 + + + FLVL + FIFO level threshold. This bit is read + only. The FIFO level threshold flag is managed only + by hardware and its setting depends on SAI block + configuration (transmitter or receiver mode). If the + SAI block is configured as transmitter: If SAI block + is configured as receiver: + 16 + 3 + + + + + SAI_BCLRFR + SAI_BCLRFR + Clear flag register + 0x3C + 0x20 + write-only + 0x00000000 + + + COVRUDR + Clear overrun / underrun. This bit is + write only. Programming this bit to 1 clears the + OVRUDR flag in the SAI_xSR register. Reading this bit + always returns the value 0. + 0 + 1 + + + CMUTEDET + Mute detection flag. This bit is write + only. Programming this bit to 1 clears the MUTEDET + flag in the SAI_xSR register. Reading this bit always + returns the value 0. + 1 + 1 + + + CWCKCFG + Clear wrong clock configuration flag. + This bit is write only. Programming this bit to 1 + clears the WCKCFG flag in the SAI_xSR register. This + bit is used only when the audio block is set as + master (MODE[1] = 0) and NODIV = 0 in the SAI_xCR1 + register. Reading this bit always returns the value + 0. + 2 + 1 + + + CCNRDY + Clear Codec not ready flag. This bit is + write only. Programming this bit to 1 clears the + CNRDY flag in the SAI_xSR register. This bit is used + only when the AC97 audio protocol is selected in the + SAI_xCR1 register. Reading this bit always returns + the value 0. + 4 + 1 + + + CAFSDET + Clear anticipated frame synchronization + detection flag. This bit is write only. Programming + this bit to 1 clears the AFSDET flag in the SAI_xSR + register. It is not used in AC97or SPDIF mode. + Reading this bit always returns the value + 0. + 5 + 1 + + + CLFSDET + Clear late frame synchronization + detection flag. This bit is write only. Programming + this bit to 1 clears the LFSDET flag in the SAI_xSR + register. This bit is not used in AC97or SPDIF mode + Reading this bit always returns the value + 0. + 6 + 1 + + + + + SAI_BDR + SAI_BDR + Data register + 0x40 + 0x20 + read-write + 0x00000000 + + + DATA + Data A write to this register loads the + FIFO provided the FIFO is not full. A read from this + register empties the FIFO if the FIFO is not + empty. + 0 + 32 + + + + + SAI_PDMCR + SAI_PDMCR + PDM control register + 0x44 + 0x20 + read-write + 0x00000000 + + + PDMEN + PDM enable + 0 + 1 + + + MICNBR + Number of microphones + 4 + 2 + + + CKEN1 + Clock enable of bitstream clock number + 1 + 8 + 1 + + + CKEN2 + Clock enable of bitstream clock number + 2 + 9 + 1 + + + CKEN3 + Clock enable of bitstream clock number + 3 + 10 + 1 + + + CKEN4 + Clock enable of bitstream clock number + 4 + 11 + 1 + + + + + SAI_PDMDLY + SAI_PDMDLY + PDM delay register + 0x48 + 0x20 + read-write + 0x00000000 + + + DLYM1L + Delay line adjust for first microphone + of pair 1 + 0 + 3 + + + DLYM1R + Delay line adjust for second microphone + of pair 1 + 4 + 3 + + + DLYM2L + Delay line for first microphone of pair + 2 + 8 + 3 + + + DLYM2R + Delay line for second microphone of pair + 2 + 12 + 3 + + + DLYM3L + Delay line for first microphone of pair + 3 + 16 + 3 + + + DLYM3R + Delay line for second microphone of pair + 3 + 20 + 3 + + + DLYM4L + Delay line for first microphone of pair + 4 + 24 + 3 + + + DLYM4R + Delay line for second microphone of pair + 4 + 28 + 3 + + + + + + + SAI1 + 0x40015800 + + SAI1 + SAI1 global interrupt + 87 + + + + SAI2 + 0x40015C00 + + SAI2 + SAI2 global interrupt + 91 + + + + SAI3 + 0x40016000 + + SAI3 + SAI3 global interrupt + 114 + + + + SDMMC1 + SDMMC1 + SDMMC + 0x52007000 + + 0x0 + 0x3FD + registers + + + SDMMC1 + SDMMC global interrupt + 49 + + + SDMMC + SDMMC global interrupt + 124 + + + + POWER + POWER + SDMMC power control register + 0x0 + 0x20 + read-write + 0x00000000 + + + PWRCTRL + SDMMC state control bits. These bits can + only be written when the SDMMC is not in the power-on + state (PWRCTRL?11). These bits are used to define the + functional state of the SDMMC signals: Any further + write will be ignored, PWRCTRL value will keep + 11. + 0 + 2 + + + VSWITCH + Voltage switch sequence start. This bit + is used to start the timing critical section of the + voltage switch sequence: + 2 + 1 + + + VSWITCHEN + Voltage switch procedure enable. This + bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). This bit is used to stop the + SDMMC_CK after the voltage switch command + response: + 3 + 1 + + + DIRPOL + Data and command direction signals + polarity selection. This bit can only be written when + the SDMMC is in the power-off state (PWRCTRL = + 00). + 4 + 1 + + + + + CLKCR + CLKCR + The SDMMC_CLKCR register controls the + SDMMC_CK output clock, the SDMMC_RX_CLK receive clock, + and the bus width. + 0x4 + 0x20 + read-write + 0x00000000 + + + CLKDIV + Clock divide factor This bit can only be + written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0). This field defines the + divide factor between the input clock (SDMMCCLK) and + the output clock (SDMMC_CK): SDMMC_CK frequency = + SDMMCCLK / [2 * CLKDIV]. 0xx: etc.. xxx: + etc.. + 0 + 10 + + + PWRSAV + Power saving configuration bit This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) For power + saving, the SDMMC_CK clock output can be disabled + when the bus is idle by setting PWRSAV: + 12 + 1 + + + WIDBUS + Wide bus mode enable bit This bit can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 14 + 2 + + + NEGEDGE + SDMMC_CK dephasing selection bit for + data and Command. This bit can only be written when + the CPSM and DPSM are not active (CPSMACT = 0 and + DPSMACT = 0). When clock division = 1 (CLKDIV = 0), + this bit has no effect. Data and Command change on + SDMMC_CK falling edge. When clock division &gt;1 + (CLKDIV &gt; 0) &amp; DDR = 0: - SDMMC_CK + edge occurs on SDMMCCLK rising edge. When clock + division >1 (CLKDIV > 0) & DDR = 1: - Data + changed on the SDMMCCLK falling edge succeeding a + SDMMC_CK edge. - SDMMC_CK edge occurs on SDMMCCLK + rising edge. - Data changed on the SDMMC_CK falling + edge succeeding a SDMMC_CK edge. - SDMMC_CK edge + occurs on SDMMCCLK rising edge. + 16 + 1 + + + HWFC_EN + Hardware flow control enable This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) When Hardware + flow control is enabled, the meaning of the TXFIFOE + and RXFIFOF flags change, please see SDMMC status + register definition in Section56.8.11. + 17 + 1 + + + DDR + Data rate signaling selection This bit + can only be written when the CPSM and DPSM are not + active (CPSMACT = 0 and DPSMACT = 0) DDR rate shall + only be selected with 4-bit or 8-bit wide bus mode. + (WIDBUS &gt; 00). DDR = 1 has no effect when + WIDBUS = 00 (1-bit wide bus). DDR rate shall only be + selected with clock division &gt;1. (CLKDIV + &gt; 0) + 18 + 1 + + + BUSSPEED + Bus speed mode selection between DS, HS, + SDR12, SDR25 and SDR50, DDR50, SDR104. This bit can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 19 + 1 + + + SELCLKRX + Receive clock selection. These bits can + only be written when the CPSM and DPSM are not active + (CPSMACT = 0 and DPSMACT = 0) + 20 + 2 + + + + + ARGR + ARGR + The SDMMC_ARGR register contains a 32-bit + command argument, which is sent to a card as part of a + command message. + 0x8 + 0x20 + read-write + 0x00000000 + + + CMDARG + Command argument. These bits can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). Command argument sent to a card as part of a + command message. If a command contains an argument, + it must be loaded into this register before writing a + command to the command register. + 0 + 32 + + + + + CMDR + CMDR + The SDMMC_CMDR register contains the command + index and command type bits. The command index is sent to + a card as part of a command message. The command type + bits control the command path state machine + (CPSM). + 0xC + 0x20 + read-write + 0x00000000 + + + CMDINDEX + Command index. This bit can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). The command index is sent to the card as part of + a command message. + 0 + 6 + + + CMDTRANS + The CPSM treats the command as a data + transfer command, stops the interrupt period, and + signals DataEnable to the DPSM This bit can only be + written by firmware when CPSM is disabled (CPSMEN = + 0). If this bit is set, the CPSM issues an end of + interrupt period and issues DataEnable signal to the + DPSM when the command is sent. + 6 + 1 + + + CMDSTOP + The CPSM treats the command as a Stop + Transmission command and signals Abort to the DPSM. + This bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). If this bit is set, the CPSM + issues the Abort signal to the DPSM when the command + is sent. + 7 + 1 + + + WAITRESP + Wait for response bits. This bit can + only be written by firmware when CPSM is disabled + (CPSMEN = 0). They are used to configure whether the + CPSM is to wait for a response, and if yes, which + kind of response. + 8 + 2 + + + WAITINT + CPSM waits for interrupt request. If + this bit is set, the CPSM disables command timeout + and waits for an card interrupt request (Response). + If this bit is cleared in the CPSM Wait state, will + cause the abort of the interrupt mode. + 10 + 1 + + + WAITPEND + CPSM Waits for end of data transfer + (CmdPend internal signal) from DPSM. This bit when + set, the CPSM waits for the end of data transfer + trigger before it starts sending a command. WAITPEND + is only taken into account when DTMODE = MMC stream + data transfer, WIDBUS = 1-bit wide bus mode, DPSMACT + = 1 and DTDIR = from host to card. + 11 + 1 + + + CPSMEN + Command path state machine (CPSM) Enable + bit This bit is written 1 by firmware, and cleared by + hardware when the CPSM enters the Idle state. If this + bit is set, the CPSM is enabled. When DTEN = 1, no + command will be transfered nor boot procedure will be + started. CPSMEN is cleared to 0. + 12 + 1 + + + DTHOLD + Hold new data block transmission and + reception in the DPSM. If this bit is set, the DPSM + will not move from the Wait_S state to the Send state + or from the Wait_R state to the Receive + state. + 13 + 1 + + + BOOTMODE + Select the boot mode procedure to be + used. This bit can only be written by firmware when + CPSM is disabled (CPSMEN = 0) + 14 + 1 + + + BOOTEN + Enable boot mode + procedure. + 15 + 1 + + + CMDSUSPEND + The CPSM treats the command as a Suspend + or Resume command and signals interrupt period + start/end. This bit can only be written by firmware + when CPSM is disabled (CPSMEN = 0). CMDSUSPEND = 1 + and CMDTRANS = 0 Suspend command, start interrupt + period when response bit BS=0. CMDSUSPEND = 1 and + CMDTRANS = 1 Resume command with data, end interrupt + period when response bit DF=1. + 16 + 1 + + + + + RESP1R + RESP1R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x14 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS1 + see Table 432 + 0 + 32 + + + + + RESP2R + RESP2R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x18 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS2 + see Table404. + 0 + 32 + + + + + RESP3R + RESP3R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x1C + 0x20 + read-only + 0x00000000 + + + CARDSTATUS3 + see Table404. + 0 + 32 + + + + + RESP4R + RESP4R + The SDMMC_RESP1/2/3/4R registers contain the + status of a card, which is part of the received + response. + 0x20 + 0x20 + read-only + 0x00000000 + + + CARDSTATUS4 + see Table404. + 0 + 32 + + + + + DTIMER + DTIMER + The SDMMC_DTIMER register contains the data + timeout period, in card bus clock periods. A counter + loads the value from the SDMMC_DTIMER register, and + starts decrementing when the data path state machine + (DPSM) enters the Wait_R or Busy state. If the timer + reaches 0 while the DPSM is in either of these states, + the timeout status flag is set. + 0x24 + 0x20 + read-write + 0x00000000 + + + DATATIME + Data and R1b busy timeout period This + bit can only be written when the CPSM and DPSM are + not active (CPSMACT = 0 and DPSMACT = 0). Data and + R1b busy timeout period expressed in card bus clock + periods. + 0 + 32 + + + + + DLENR + DLENR + The SDMMC_DLENR register contains the number + of data bytes to be transferred. The value is loaded into + the data counter when data transfer starts. + 0x28 + 0x20 + read-write + 0x00000000 + + + DATALENGTH + Data length value This register can only + be written by firmware when DPSM is inactive (DPSMACT + = 0). Number of data bytes to be transferred. When + DDR = 1 DATALENGTH is truncated to a multiple of 2. + (The last odd byte is not transfered) When DATALENGTH + = 0 no data will be transfered, when requested by a + CPSMEN and CMDTRANS = 1 also no command will be + transfered. DTEN and CPSMEN are cleared to + 0. + 0 + 25 + + + + + DCTRL + DCTRL + The SDMMC_DCTRL register control the data + path state machine (DPSM). + 0x2C + 0x20 + read-write + 0x00000000 + + + DTEN + Data transfer enable bit This bit can + only be written by firmware when DPSM is inactive + (DPSMACT = 0). This bit is cleared by Hardware when + data transfer completes. This bit shall only be used + to transfer data when no associated data transfer + command is used, i.e. shall not be used with SD or + eMMC cards. + 0 + 1 + + + DTDIR + Data transfer direction selection This + bit can only be written by firmware when DPSM is + inactive (DPSMACT = 0). + 1 + 1 + + + DTMODE + Data transfer mode selection. This bit + can only be written by firmware when DPSM is inactive + (DPSMACT = 0). + 2 + 2 + + + DBLOCKSIZE + Data block size This bit can only be + written by firmware when DPSM is inactive (DPSMACT = + 0). Define the data block length when the block data + transfer mode is selected: When DATALENGTH is not a + multiple of DBLOCKSIZE, the transfered data is + truncated at a multiple of DBLOCKSIZE. (Any remain + data will not be transfered.) When DDR = 1, + DBLOCKSIZE = 0000 shall not be used. (No data will be + transfered) + 4 + 4 + + + RWSTART + Read wait start. If this bit is set, + read wait operation starts. + 8 + 1 + + + RWSTOP + Read wait stop This bit is written by + firmware and auto cleared by hardware when the DPSM + moves from the READ_WAIT state to the WAIT_R or IDLE + state. + 9 + 1 + + + RWMOD + Read wait mode. This bit can only be + written by firmware when DPSM is inactive (DPSMACT = + 0). + 10 + 1 + + + SDIOEN + SD I/O interrupt enable functions This + bit can only be written by firmware when DPSM is + inactive (DPSMACT = 0). If this bit is set, the DPSM + enables the SD I/O card specific interrupt + operation. + 11 + 1 + + + BOOTACKEN + Enable the reception of the boot + acknowledgment. This bit can only be written by + firmware when DPSM is inactive (DPSMACT = + 0). + 12 + 1 + + + FIFORST + FIFO reset, will flush any remaining + data. This bit can only be written by firmware when + IDMAEN= 0 and DPSM is active (DPSMACT = 1). This bit + will only take effect when a transfer error or + transfer hold occurs. + 13 + 1 + + + + + DCNTR + DCNTR + The SDMMC_DCNTR register loads the value + from the data length register (see SDMMC_DLENR) when the + DPSM moves from the Idle state to the Wait_R or Wait_S + state. As data is transferred, the counter decrements the + value until it reaches 0. The DPSM then moves to the Idle + state and when there has been no error, the data status + end flag (DATAEND) is set. + 0x30 + 0x20 + read-only + 0x00000000 + + + DATACOUNT + Data count value When read, the number + of remaining data bytes to be transferred is + returned. Write has no effect. + 0 + 25 + + + + + STAR + STAR + The SDMMC_STAR register is a read-only + register. It contains two types of flag:Static flags + (bits [29,21,11:0]): these bits remain asserted until + they are cleared by writing to the SDMMC interrupt Clear + register (see SDMMC_ICR)Dynamic flags (bits [20:12]): + these bits change state depending on the state of the + underlying logic (for example, FIFO full and empty flags + are asserted and de-asserted as data while written to the + FIFO) + 0x34 + 0x20 + read-only + 0x00000000 + + + CCRCFAIL + Command response received (CRC check + failed). Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 0 + 1 + + + DCRCFAIL + Data block sent/received (CRC check + failed). Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 1 + 1 + + + CTIMEOUT + Command response timeout. Interrupt flag + is cleared by writing corresponding interrupt clear + bit in SDMMC_ICR. The Command Timeout period has a + fixed value of 64 SDMMC_CK clock + periods. + 2 + 1 + + + DTIMEOUT + Data timeout. Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 3 + 1 + + + TXUNDERR + Transmit FIFO underrun error or IDMA + read transfer error. Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 4 + 1 + + + RXOVERR + Received FIFO overrun error or IDMA + write transfer error. Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 5 + 1 + + + CMDREND + Command response received (CRC check + passed, or no CRC). Interrupt flag is cleared by + writing corresponding interrupt clear bit in + SDMMC_ICR. + 6 + 1 + + + CMDSENT + Command sent (no response required). + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 7 + 1 + + + DATAEND + Data transfer ended correctly. (data + counter, DATACOUNT is zero and no errors occur). + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 8 + 1 + + + DHOLD + Data transfer Hold. Interrupt flag is + cleared by writing corresponding interrupt clear bit + in SDMMC_ICR. + 9 + 1 + + + DBCKEND + Data block sent/received. (CRC check + passed) and DPSM moves to the READWAIT state. + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 10 + 1 + + + DABORT + Data transfer aborted by CMD12. + Interrupt flag is cleared by writing corresponding + interrupt clear bit in SDMMC_ICR. + 11 + 1 + + + DPSMACT + Data path state machine active, i.e. not + in Idle state. This is a hardware status flag only, + does not generate an interrupt. + 12 + 1 + + + CPSMACT + Command path state machine active, i.e. + not in Idle state. This is a hardware status flag + only, does not generate an interrupt. + 13 + 1 + + + TXFIFOHE + Transmit FIFO half empty At least half + the number of words can be written into the FIFO. + This bit is cleared when the FIFO becomes half+1 + full. + 14 + 1 + + + RXFIFOHF + Receive FIFO half full There are at + least half the number of words in the FIFO. This bit + is cleared when the FIFO becomes half+1 + empty. + 15 + 1 + + + TXFIFOF + Transmit FIFO full This is a hardware + status flag only, does not generate an interrupt. + This bit is cleared when one FIFO location becomes + empty. + 16 + 1 + + + RXFIFOF + Receive FIFO full This bit is cleared + when one FIFO location becomes empty. + 17 + 1 + + + TXFIFOE + Transmit FIFO empty This bit is cleared + when one FIFO location becomes full. + 18 + 1 + + + RXFIFOE + Receive FIFO empty This is a hardware + status flag only, does not generate an interrupt. + This bit is cleared when one FIFO location becomes + full. + 19 + 1 + + + BUSYD0 + Inverted value of SDMMC_D0 line (Busy), + sampled at the end of a CMD response and a second + time 2 SDMMC_CK cycles after the CMD response. This + bit is reset to not busy when the SDMMCD0 line + changes from busy to not busy. This bit does not + signal busy due to data transfer. This is a hardware + status flag only, it does not generate an + interrupt. + 20 + 1 + + + BUSYD0END + end of SDMMC_D0 Busy following a CMD + response detected. This indicates only end of busy + following a CMD response. This bit does not signal + busy due to data transfer. Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 21 + 1 + + + SDIOIT + SDIO interrupt received. Interrupt flag + is cleared by writing corresponding interrupt clear + bit in SDMMC_ICR. + 22 + 1 + + + ACKFAIL + Boot acknowledgment received (boot + acknowledgment check fail). Interrupt flag is cleared + by writing corresponding interrupt clear bit in + SDMMC_ICR. + 23 + 1 + + + ACKTIMEOUT + Boot acknowledgment timeout. Interrupt + flag is cleared by writing corresponding interrupt + clear bit in SDMMC_ICR. + 24 + 1 + + + VSWEND + Voltage switch critical timing section + completion. Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 25 + 1 + + + CKSTOP + SDMMC_CK stopped in Voltage switch + procedure. Interrupt flag is cleared by writing + corresponding interrupt clear bit in + SDMMC_ICR. + 26 + 1 + + + IDMATE + IDMA transfer error. Interrupt flag is + cleared by writing corresponding interrupt clear bit + in SDMMC_ICR. + 27 + 1 + + + IDMABTC + IDMA buffer transfer complete. interrupt + flag is cleared by writing corresponding interrupt + clear bit in SDMMC_ICR. + 28 + 1 + + + + + ICR + ICR + The SDMMC_ICR register is a write-only + register. Writing a bit with 1 clears the corresponding + bit in the SDMMC_STAR status register. + 0x38 + 0x20 + read-write + 0x00000000 + + + CCRCFAILC + CCRCFAIL flag clear bit Set by software + to clear the CCRCFAIL flag. + 0 + 1 + + + DCRCFAILC + DCRCFAIL flag clear bit Set by software + to clear the DCRCFAIL flag. + 1 + 1 + + + CTIMEOUTC + CTIMEOUT flag clear bit Set by software + to clear the CTIMEOUT flag. + 2 + 1 + + + DTIMEOUTC + DTIMEOUT flag clear bit Set by software + to clear the DTIMEOUT flag. + 3 + 1 + + + TXUNDERRC + TXUNDERR flag clear bit Set by software + to clear TXUNDERR flag. + 4 + 1 + + + RXOVERRC + RXOVERR flag clear bit Set by software + to clear the RXOVERR flag. + 5 + 1 + + + CMDRENDC + CMDREND flag clear bit Set by software + to clear the CMDREND flag. + 6 + 1 + + + CMDSENTC + CMDSENT flag clear bit Set by software + to clear the CMDSENT flag. + 7 + 1 + + + DATAENDC + DATAEND flag clear bit Set by software + to clear the DATAEND flag. + 8 + 1 + + + DHOLDC + DHOLD flag clear bit Set by software to + clear the DHOLD flag. + 9 + 1 + + + DBCKENDC + DBCKEND flag clear bit Set by software + to clear the DBCKEND flag. + 10 + 1 + + + DABORTC + DABORT flag clear bit Set by software to + clear the DABORT flag. + 11 + 1 + + + BUSYD0ENDC + BUSYD0END flag clear bit Set by software + to clear the BUSYD0END flag. + 21 + 1 + + + SDIOITC + SDIOIT flag clear bit Set by software to + clear the SDIOIT flag. + 22 + 1 + + + ACKFAILC + ACKFAIL flag clear bit Set by software + to clear the ACKFAIL flag. + 23 + 1 + + + ACKTIMEOUTC + ACKTIMEOUT flag clear bit Set by + software to clear the ACKTIMEOUT flag. + 24 + 1 + + + VSWENDC + VSWEND flag clear bit Set by software to + clear the VSWEND flag. + 25 + 1 + + + CKSTOPC + CKSTOP flag clear bit Set by software to + clear the CKSTOP flag. + 26 + 1 + + + IDMATEC + IDMA transfer error clear bit Set by + software to clear the IDMATE flag. + 27 + 1 + + + IDMABTCC + IDMA buffer transfer complete clear bit + Set by software to clear the IDMABTC + flag. + 28 + 1 + + + + + MASKR + MASKR + The interrupt mask register determines which + status flags generate an interrupt request by setting the + corresponding bit to 1. + 0x3C + 0x20 + read-write + 0x00000000 + + + CCRCFAILIE + Command CRC fail interrupt enable Set + and cleared by software to enable/disable interrupt + caused by command CRC failure. + 0 + 1 + + + DCRCFAILIE + Data CRC fail interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data CRC failure. + 1 + 1 + + + CTIMEOUTIE + Command timeout interrupt enable Set and + cleared by software to enable/disable interrupt + caused by command timeout. + 2 + 1 + + + DTIMEOUTIE + Data timeout interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data timeout. + 3 + 1 + + + TXUNDERRIE + Tx FIFO underrun error interrupt enable + Set and cleared by software to enable/disable + interrupt caused by Tx FIFO underrun + error. + 4 + 1 + + + RXOVERRIE + Rx FIFO overrun error interrupt enable + Set and cleared by software to enable/disable + interrupt caused by Rx FIFO overrun + error. + 5 + 1 + + + CMDRENDIE + Command response received interrupt + enable Set and cleared by software to enable/disable + interrupt caused by receiving command + response. + 6 + 1 + + + CMDSENTIE + Command sent interrupt enable Set and + cleared by software to enable/disable interrupt + caused by sending command. + 7 + 1 + + + DATAENDIE + Data end interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data end. + 8 + 1 + + + DHOLDIE + Data hold interrupt enable Set and + cleared by software to enable/disable the interrupt + generated when sending new data is hold in the DPSM + Wait_S state. + 9 + 1 + + + DBCKENDIE + Data block end interrupt enable Set and + cleared by software to enable/disable interrupt + caused by data block end. + 10 + 1 + + + DABORTIE + Data transfer aborted interrupt enable + Set and cleared by software to enable/disable + interrupt caused by a data transfer being + aborted. + 11 + 1 + + + TXFIFOHEIE + Tx FIFO half empty interrupt enable Set + and cleared by software to enable/disable interrupt + caused by Tx FIFO half empty. + 14 + 1 + + + RXFIFOHFIE + Rx FIFO half full interrupt enable Set + and cleared by software to enable/disable interrupt + caused by Rx FIFO half full. + 15 + 1 + + + RXFIFOFIE + Rx FIFO full interrupt enable Set and + cleared by software to enable/disable interrupt + caused by Rx FIFO full. + 17 + 1 + + + TXFIFOEIE + Tx FIFO empty interrupt enable Set and + cleared by software to enable/disable interrupt + caused by Tx FIFO empty. + 18 + 1 + + + BUSYD0ENDIE + BUSYD0END interrupt enable Set and + cleared by software to enable/disable the interrupt + generated when SDMMC_D0 signal changes from busy to + NOT busy following a CMD response. + 21 + 1 + + + SDIOITIE + SDIO mode interrupt received interrupt + enable Set and cleared by software to enable/disable + the interrupt generated when receiving the SDIO mode + interrupt. + 22 + 1 + + + ACKFAILIE + Acknowledgment Fail interrupt enable Set + and cleared by software to enable/disable interrupt + caused by acknowledgment Fail. + 23 + 1 + + + ACKTIMEOUTIE + Acknowledgment timeout interrupt enable + Set and cleared by software to enable/disable + interrupt caused by acknowledgment + timeout. + 24 + 1 + + + VSWENDIE + Voltage switch critical timing section + completion interrupt enable Set and cleared by + software to enable/disable the interrupt generated + when voltage switch critical timing section + completion. + 25 + 1 + + + CKSTOPIE + Voltage Switch clock stopped interrupt + enable Set and cleared by software to enable/disable + interrupt caused by Voltage Switch clock + stopped. + 26 + 1 + + + IDMABTCIE + IDMA buffer transfer complete interrupt + enable Set and cleared by software to enable/disable + the interrupt generated when the IDMA has transferred + all data belonging to a memory buffer. + 28 + 1 + + + + + ACKTIMER + ACKTIMER + The SDMMC_ACKTIMER register contains the + acknowledgment timeout period, in SDMMC_CK bus clock + periods. A counter loads the value from the + SDMMC_ACKTIMER register, and starts decrementing when the + data path state machine (DPSM) enters the Wait_Ack state. + If the timer reaches 0 while the DPSM is in this states, + the acknowledgment timeout status flag is + set. + 0x40 + 0x20 + read-write + 0x00000000 + + + ACKTIME + Boot acknowledgment timeout period This + bit can only be written by firmware when CPSM is + disabled (CPSMEN = 0). Boot acknowledgment timeout + period expressed in card bus clock + periods. + 0 + 25 + + + + + IDMACTRLR + IDMACTRLR + The receive and transmit FIFOs can be read + or written as 32-bit wide registers. The FIFOs contain 32 + entries on 32 sequential addresses. This allows the CPU + to use its load and store multiple operands to read + from/write to the FIFO. + 0x50 + 0x20 + read-write + 0x00000000 + + + IDMAEN + IDMA enable This bit can only be written + by firmware when DPSM is inactive (DPSMACT = + 0). + 0 + 1 + + + IDMABMODE + Buffer mode selection. This bit can only + be written by firmware when DPSM is inactive (DPSMACT + = 0). + 1 + 1 + + + IDMABACT + Double buffer mode active buffer + indication This bit can only be written by firmware + when DPSM is inactive (DPSMACT = 0). When IDMA is + enabled this bit is toggled by + hardware. + 2 + 1 + + + + + IDMABSIZER + IDMABSIZER + The SDMMC_IDMABSIZER register contains the + buffers size when in double buffer + configuration. + 0x54 + 0x20 + read-write + 0x00000000 + + + IDMABNDT + Number of transfers per buffer. This + 8-bit value shall be multiplied by 8 to get the size + of the buffer in 32-bit words and by 32 to get the + size of the buffer in bytes. Example: IDMABNDT = + 0x01: buffer size = 8 words = 32 bytes. These bits + can only be written by firmware when DPSM is inactive + (DPSMACT = 0). + 5 + 8 + + + + + IDMABASE0R + IDMABASE0R + The SDMMC_IDMABASE0R register contains the + memory buffer base address in single buffer configuration + and the buffer 0 base address in double buffer + configuration. + 0x58 + 0x20 + read-write + 0x00000000 + + + IDMABASE0 + Buffer 0 memory base address bits + [31:2], shall be word aligned (bit [1:0] are always 0 + and read only). This register can be written by + firmware when DPSM is inactive (DPSMACT = 0), and can + dynamically be written by firmware when DPSM active + (DPSMACT = 1) and memory buffer 0 is inactive + (IDMABACT = 1). + 0 + 32 + + + + + IDMABASE1R + IDMABASE1R + The SDMMC_IDMABASE1R register contains the + double buffer configuration second buffer memory base + address. + 0x5C + 0x20 + read-write + 0x00000000 + + + IDMABASE1 + Buffer 1 memory base address, shall be + word aligned (bit [1:0] are always 0 and read only). + This register can be written by firmware when DPSM is + inactive (DPSMACT = 0), and can dynamically be + written by firmware when DPSM active (DPSMACT = 1) + and memory buffer 1 is inactive (IDMABACT = + 0). + 0 + 32 + + + + + FIFOR + FIFOR + The receive and transmit FIFOs can be only + read or written as word (32-bit) wide registers. The + FIFOs contain 16 entries on sequential addresses. This + allows the CPU to use its load and store multiple + operands to read from/write to the FIFO.When accessing + SDMMC_FIFOR with half word or byte access an AHB bus + fault is generated. + 0x80 + 0x20 + read-write + 0x00000000 + + + FIFODATA + Receive and transmit FIFO data This + register can only be read or written by firmware when + the DPSM is active (DPSMACT=1). The FIFO data + occupies 16 entries of 32-bit words. + 0 + 32 + + + + + VER + VER + SDMMC IP version register + 0x3F4 + 0x20 + read-only + 0x00000010 + + + MINREV + IP minor revision number. + 0 + 4 + + + MAJREV + IP major revision number. + 4 + 4 + + + + + ID + ID + SDMMC IP identification + register + 0x3F8 + 0x20 + read-only + 0x00140022 + + + IP_ID + SDMMC IP identification. + 0 + 32 + + + + + RESPCMDR + RESPCMDR + SDMMC command response + register + 0x10 + 0x20 + read-only + 0xA3C5DD01 + + + RESPCMD + Response command index + 0 + 6 + + + + + + + SDMMC2 + 0x48022400 + + + VREFBUF + VREFBUF + VREFBUF + 0x58003C00 + + 0x0 + 0x400 + registers + + + + CSR + CSR + VREFBUF control and status + register + 0x0 + 0x20 + 0x00000002 + + + ENVR + Voltage reference buffer mode enable + This bit is used to enable the voltage reference + buffer mode. + 0 + 1 + read-write + + + HIZ + High impedance mode This bit controls + the analog switch to connect or not the VREF+ pin. + Refer to Table196: VREF buffer modes for the mode + descriptions depending on ENVR bit + configuration. + 1 + 1 + read-write + + + VRR + Voltage reference buffer + ready + 3 + 1 + read-only + + + VRS + Voltage reference scale These bits + select the value generated by the voltage reference + buffer. Other: Reserved + 4 + 3 + read-write + + + + + CCR + CCR + VREFBUF calibration control + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TRIM + Trimming code These bits are + automatically initialized after reset with the + trimming value stored in the Flash memory during the + production test. Writing into these bits allows to + tune the internal reference buffer + voltage. + 0 + 6 + + + + + + + IWDG + IWDG + IWDG + 0x58004800 + + 0x0 + 0x400 + registers + + + + KR + KR + Key register + 0x0 + 0x20 + write-only + 0x00000000 + + + KEY + Key value (write only, read 0x0000) + These bits must be written by software at regular + intervals with the key value 0xAAAA, otherwise the + watchdog generates a reset when the counter reaches + 0. Writing the key value 0x5555 to enable access to + the IWDG_PR, IWDG_RLR and IWDG_WINR registers (see + Section23.3.6: Register access protection) Writing + the key value CCCCh starts the watchdog (except if + the hardware watchdog option is + selected) + 0 + 16 + + + + + PR + PR + Prescaler register + 0x4 + 0x20 + read-write + 0x00000000 + + + PR + Prescaler divider These bits are write + access protected see Section23.3.6: Register access + protection. They are written by software to select + the prescaler divider feeding the counter clock. PVU + bit of IWDG_SR must be reset in order to be able to + change the prescaler divider. Note: Reading this + register returns the prescaler value from the VDD + voltage domain. This value may not be up to + date/valid if a write operation to this register is + ongoing. For this reason the value read from this + register is valid only when the PVU bit in the + IWDG_SR register is reset. + 0 + 3 + + + + + RLR + RLR + Reload register + 0x8 + 0x20 + read-write + 0x00000FFF + + + RL + Watchdog counter reload value These bits + are write access protected see Section23.3.6. They + are written by software to define the value to be + loaded in the watchdog counter each time the value + 0xAAAA is written in the IWDG_KR register. The + watchdog counter counts down from this value. The + timeout period is a function of this value and the + clock prescaler. Refer to the datasheet for the + timeout information. The RVU bit in the IWDG_SR + register must be reset in order to be able to change + the reload value. Note: Reading this register returns + the reload value from the VDD voltage domain. This + value may not be up to date/valid if a write + operation to this register is ongoing on this + register. For this reason the value read from this + register is valid only when the RVU bit in the + IWDG_SR register is reset. + 0 + 12 + + + + + SR + SR + Status register + 0xC + 0x20 + read-only + 0x00000000 + + + PVU + Watchdog prescaler value update This bit + is set by hardware to indicate that an update of the + prescaler value is ongoing. It is reset by hardware + when the prescaler update operation is completed in + the VDD voltage domain (takes up to 5 RC 40 kHz + cycles). Prescaler value can be updated only when PVU + bit is reset. + 0 + 1 + + + RVU + Watchdog counter reload value update + This bit is set by hardware to indicate that an + update of the reload value is ongoing. It is reset by + hardware when the reload value update operation is + completed in the VDD voltage domain (takes up to 5 RC + 40 kHz cycles). Reload value can be updated only when + RVU bit is reset. + 1 + 1 + + + WVU + Watchdog counter window value update + This bit is set by hardware to indicate that an + update of the window value is ongoing. It is reset by + hardware when the reload value update operation is + completed in the VDD voltage domain (takes up to 5 RC + 40 kHz cycles). Window value can be updated only when + WVU bit is reset. This bit is generated only if + generic window = 1 + 2 + 1 + + + + + WINR + WINR + Window register + 0x10 + 0x20 + read-write + 0x00000FFF + + + WIN + Watchdog counter window value These bits + are write access protected see Section23.3.6. These + bits contain the high limit of the window value to be + compared to the downcounter. To prevent a reset, the + downcounter must be reloaded when its value is lower + than the window register value and greater than 0x0 + The WVU bit in the IWDG_SR register must be reset in + order to be able to change the reload value. Note: + Reading this register returns the reload value from + the VDD voltage domain. This value may not be valid + if a write operation to this register is ongoing. For + this reason the value read from this register is + valid only when the WVU bit in the IWDG_SR register + is reset. + 0 + 12 + + + + + + + WWDG + WWDG + WWDG + 0x50003000 + + 0x0 + 0x400 + registers + + + WWDG1 + Window Watchdog interrupt + 0 + + + WWDG1_RST + Window Watchdog interrupt + 143 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x0000007F + + + T + 7-bit counter (MSB to LSB) These bits + contain the value of the watchdog counter. It is + decremented every (4096 x 2WDGTB[1:0]) PCLK cycles. A + reset is produced when it is decremented from 0x40 to + 0x3F (T6 becomes cleared). + 0 + 7 + + + WDGA + Activation bit This bit is set by + software and only cleared by hardware after a reset. + When WDGA=1, the watchdog can generate a + reset. + 7 + 1 + + + + + CFR + CFR + Configuration register + 0x4 + 0x20 + read-write + 0x0000007F + + + W + 7-bit window value These bits contain + the window value to be compared to the + downcounter. + 0 + 7 + + + WDGTB + Timer base The time base of the + prescaler can be modified as follows: + 11 + 2 + + + EWI + Early wakeup interrupt When set, an + interrupt occurs whenever the counter reaches the + value 0x40. This interrupt is only cleared by + hardware after a reset. + 9 + 1 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-write + 0x00000000 + + + EWIF + Early wakeup interrupt flag This bit is + set by hardware when the counter has reached the + value 0x40. It must be cleared by software by writing + 0. A write of 1 has no effect. This bit is also set + if the interrupt is not enabled. + 0 + 1 + + + + + + + PWR + PWR + PWR + 0x58024800 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + PWR control register 1 + 0x0 + 0x20 + read-write + 0xF000C000 + + + LPDS + Low-power Deepsleep with SVOS3 (SVOS4 + and SVOS5 always use low-power, regardless of the + setting of this bit) + 0 + 1 + + + PVDE + Programmable voltage detector + enable + 4 + 1 + + + PLS + Programmable voltage detector level + selection These bits select the voltage threshold + detected by the PVD. Note: Refer to Section + Electrical characteristics of the product datasheet + for more details. + 5 + 3 + + + DBP + Disable backup domain write protection + In reset state, the RCC_BDCR register, the RTC + registers (including the backup registers), BREN and + MOEN bits in PWR_CR2 register, are protected against + parasitic write access. This bit must be set to + enable write access to these registers. + 8 + 1 + + + FLPS + Flash low-power mode in DStop mode This + bit allows to obtain the best trade-off between + low-power consumption and restart time when exiting + from DStop mode. When it is set, the Flash memory + enters low-power mode when D1 domain is in DStop + mode. + 9 + 1 + + + SVOS + System Stop mode voltage scaling + selection These bits control the VCORE voltage level + in system Stop mode, to obtain the best trade-off + between power consumption and + performance. + 14 + 2 + + + AVDEN + Peripheral voltage monitor on VDDA + enable + 16 + 1 + + + ALS + Analog voltage detector level selection + These bits select the voltage threshold detected by + the AVD. + 17 + 2 + + + + + CSR1 + CSR1 + PWR control status register 1 + 0x4 + 0x20 + read-only + 0x00004000 + + + PVDO + Programmable voltage detect output This + bit is set and cleared by hardware. It is valid only + if the PVD has been enabled by the PVDE bit. Note: + since the PVD is disabled in Standby mode, this bit + is equal to 0 after Standby or reset until the PVDE + bit is set. + 4 + 1 + + + ACTVOSRDY + Voltage levels ready bit for currently + used VOS and SDLEVEL This bit is set to 1 by hardware + when the voltage regulator and the SD converter are + both disabled and Bypass mode is selected in PWR + control register 3 (PWR_CR3). + 13 + 1 + + + ACTVOS + VOS currently applied for VCORE voltage + scaling selection. These bits reflect the last VOS + value applied to the PMU. + 14 + 2 + + + AVDO + Analog voltage detector output on VDDA + This bit is set and cleared by hardware. It is valid + only if AVD on VDDA is enabled by the AVDEN bit. + Note: Since the AVD is disabled in Standby mode, this + bit is equal to 0 after Standby or reset until the + AVDEN bit is set. + 16 + 1 + + + + + CR2 + CR2 + This register is not reset by wakeup from + Standby mode, RESET signal and VDD POR. It is only reset + by VSW POR and VSWRST reset. This register shall not be + accessed when VSWRST bit in RCC_BDCR register resets the + VSW domain.After reset, PWR_CR2 register is + write-protected. Prior to modifying its content, the DBP + bit in PWR_CR1 register must be set to disable the write + protection. + 0x8 + 0x20 + 0x00000000 + + + BREN + Backup regulator enable When set, the + Backup regulator (used to maintain the backup RAM + content in Standby and VBAT modes) is enabled. If + BREN is reset, the backup regulator is switched off. + The backup RAM can still be used in Run and Stop + modes. However, its content will be lost in Standby + and VBAT modes. If BREN is set, the application must + wait till the Backup Regulator Ready flag (BRRDY) is + set to indicate that the data written into the SRAM + will be maintained in Standby and VBAT + modes. + 0 + 1 + read-write + + + MONEN + VBAT and temperature monitoring enable + When set, the VBAT supply and temperature monitoring + is enabled. + 4 + 1 + read-write + + + BRRDY + Backup regulator ready This bit is set + by hardware to indicate that the Backup regulator is + ready. + 16 + 1 + read-only + + + VBATL + VBAT level monitoring versus low + threshold + 20 + 1 + read-only + + + VBATH + VBAT level monitoring versus high + threshold + 21 + 1 + read-only + + + TEMPL + Temperature level monitoring versus low + threshold + 22 + 1 + read-only + + + TEMPH + Temperature level monitoring versus high + threshold + 23 + 1 + read-only + + + + + CR3 + CR3 + Reset only by POR only, not reset by wakeup + from Standby mode and RESET pad. The lower byte of this + register is written once after POR and shall be written + before changing VOS level or ck_sys clock frequency. No + limitation applies to the upper bytes.Programming data + corresponding to an invalid combination of SDLEVEL, + SDEXTHP, SDEN, LDOEN and BYPASS bits (see Table9) will be + ignored: data will not be written, the written-once + mechanism will lock the register and any further write + access will be ignored. The default supply configuration + will be kept and the ACTVOSRDY bit in PWR control status + register 1 (PWR_CSR1) will go on indicating invalid + voltage levels. The system shall be power cycled before + writing a new value. + 0xC + 0x20 + 0x00000006 + + + BYPASS + Power management unit + bypass + 0 + 1 + read-write + + + LDOEN + Low drop-out regulator + enable + 1 + 1 + read-write + + + SCUEN + SD converter Enable + 2 + 1 + read-write + + + VBE + VBAT charging enable + 8 + 1 + read-write + + + VBRS + VBAT charging resistor + selection + 9 + 1 + read-write + + + USB33DEN + VDD33USB voltage level detector + enable. + 24 + 1 + read-write + + + USBREGEN + USB regulator enable. + 25 + 1 + read-write + + + USB33RDY + USB supply ready. + 26 + 1 + read-only + + + + + CPUCR + CPUCR + This register allows controlling CPU1 + power. + 0x10 + 0x20 + 0x00000000 + + + PDDS_D1 + D1 domain Power Down Deepsleep + selection. This bit allows CPU1 to define the + Deepsleep mode for D1 domain. + 0 + 1 + read-write + + + PDDS_D2 + D2 domain Power Down Deepsleep. This bit + allows CPU1 to define the Deepsleep mode for D2 + domain. + 1 + 1 + read-write + + + PDDS_D3 + System D3 domain Power Down Deepsleep. + This bit allows CPU1 to define the Deepsleep mode for + System D3 domain. + 2 + 1 + read-write + + + STOPF + STOP flag This bit is set by hardware + and cleared only by any reset or by setting the CPU1 + CSSF bit. + 5 + 1 + read-only + + + SBF + System Standby flag This bit is set by + hardware and cleared only by a POR (Power-on Reset) + or by setting the CPU1 CSSF bit + 6 + 1 + read-only + + + SBF_D1 + D1 domain DStandby flag This bit is set + by hardware and cleared by any system reset or by + setting the CPU1 CSSF bit. Once set, this bit can be + cleared only when the D1 domain is no longer in + DStandby mode. + 7 + 1 + read-only + + + SBF_D2 + D2 domain DStandby flag This bit is set + by hardware and cleared by any system reset or by + setting the CPU1 CSSF bit. Once set, this bit can be + cleared only when the D2 domain is no longer in + DStandby mode. + 8 + 1 + read-only + + + CSSF + Clear D1 domain CPU1 Standby, Stop and + HOLD flags (always read as 0) This bit is cleared to + 0 by hardware. + 9 + 1 + read-write + + + RUN_D3 + Keep system D3 domain in Run mode + regardless of the CPU sub-systems modes + 11 + 1 + read-write + + + + + D3CR + D3CR + This register allows controlling D3 domain + power.Following reset VOSRDY will be read 1 by + software + 0x18 + 0x20 + 0x00004000 + + + VOSRDY + VOS Ready bit for VCORE voltage scaling + output selection. This bit is set to 1 by hardware + when Bypass mode is selected in PWR control register + 3 (PWR_CR3). + 13 + 1 + read-only + + + VOS + Voltage scaling selection according to + performance These bits control the VCORE voltage + level and allow to obtains the best trade-off between + power consumption and performance: When increasing + the performance, the voltage scaling shall be changed + before increasing the system frequency. When + decreasing performance, the system frequency shall + first be decreased before changing the voltage + scaling. + 14 + 2 + read-write + + + + + WKUPCR + WKUPCR + reset only by system reset, not reset by + wakeup from Standby mode5 wait states are required when + writing this register (when clearing a WKUPF bit in + PWR_WKUPFR, the AHB write access will complete after the + WKUPF has been cleared). + 0x20 + 0x20 + read-write + 0x00000000 + + + WKUPC + Clear Wakeup pin flag for WKUP. These + bits are always read as 0. + 0 + 6 + + + + + WKUPFR + WKUPFR + reset only by system reset, not reset by + wakeup from Standby mode + 0x24 + 0x20 + read-write + 0x00000000 + + + WKUPF1 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 0 + 1 + + + WKUPF2 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 1 + 1 + + + WKUPF3 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 2 + 1 + + + WKUPF4 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 3 + 1 + + + WKUPF5 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 4 + 1 + + + WKUPF6 + Wakeup pin WKUPF flag. This bit is set + by hardware and cleared only by a Reset pin or by + setting the WKUPCn+1 bit in the PWR wakeup clear + register (PWR_WKUPCR). + 5 + 1 + + + + + WKUPEPR + WKUPEPR + Reset only by system reset, not reset by + wakeup from Standby mode + 0x28 + 0x20 + read-write + 0x00000000 + + + WKUPEN1 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 0 + 1 + + + WKUPEN2 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 1 + 1 + + + WKUPEN3 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 2 + 1 + + + WKUPEN4 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 3 + 1 + + + WKUPEN5 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 4 + 1 + + + WKUPEN6 + Enable Wakeup Pin WKUPn+1 Each bit is + set and cleared by software. Note: An additional + wakeup event is detected if WKUPn+1 pin is enabled + (by setting the WKUPENn+1 bit) when WKUPn+1 pin level + is already high when WKUPPn+1 selects rising edge, or + low when WKUPPn+1 selects falling edge. + 5 + 1 + + + WKUPP1 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 8 + 1 + + + WKUPP2 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 9 + 1 + + + WKUPP3 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 10 + 1 + + + WKUPP4 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 11 + 1 + + + WKUPP5 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 12 + 1 + + + WKUPP6 + Wakeup pin polarity bit for WKUPn-7 + These bits define the polarity used for event + detection on WKUPn-7 external wakeup + pin. + 13 + 1 + + + WKUPPUPD1 + Wakeup pin pull + configuration + 16 + 2 + + + WKUPPUPD2 + Wakeup pin pull + configuration + 18 + 2 + + + WKUPPUPD3 + Wakeup pin pull + configuration + 20 + 2 + + + WKUPPUPD4 + Wakeup pin pull + configuration + 22 + 2 + + + WKUPPUPD5 + Wakeup pin pull + configuration + 24 + 2 + + + WKUPPUPD6 + Wakeup pin pull configuration for + WKUP(truncate(n/2)-7) These bits define the I/O pad + pull configuration used when WKUPEN(truncate(n/2)-7) + = 1. The associated GPIO port pull configuration + shall be set to the same value or to 00. The Wakeup + pin pull configuration is kept in Standby + mode. + 26 + 2 + + + + + + + SPI1 + Serial peripheral interface + SPI + 0x40013000 + + 0x0 + 0x400 + registers + + + SPI1 + SPI1 global interrupt + 35 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + 0x00000000 + + + IOLOCK + Locking the AF configuration of + associated IOs + 16 + 1 + read-only + + + TCRCI + CRC calculation initialization pattern + control for transmitter + 15 + 1 + read-write + + + RCRCI + CRC calculation initialization pattern + control for receiver + 14 + 1 + read-write + + + CRC33_17 + 32-bit CRC polynomial + configuration + 13 + 1 + read-write + + + SSI + Internal SS signal input + level + 12 + 1 + read-write + + + HDDIR + Rx/Tx direction at Half-duplex + mode + 11 + 1 + read-write + + + CSUSP + Master SUSPend request + 10 + 1 + write-only + + + CSTART + Master transfer start + 9 + 1 + read-only + + + MASRX + Master automatic SUSP in Receive + mode + 8 + 1 + read-write + + + SPE + Serial Peripheral Enable + 0 + 1 + read-write + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + 0x00000000 + + + TSER + Number of data transfer extension to be + reload into TSIZE just when a previous + 16 + 16 + read-only + + + TSIZE + Number of data at current + transfer + 0 + 16 + read-write + + + + + CFG1 + CFG1 + configuration register 1 + 0x8 + 0x20 + read-write + 0x00070007 + + + MBR + Master baud rate + 28 + 3 + + + CRCEN + Hardware CRC computation + enable + 22 + 1 + + + CRCSIZE + Length of CRC frame to be transacted and + compared + 16 + 5 + + + TXDMAEN + Tx DMA stream enable + 15 + 1 + + + RXDMAEN + Rx DMA stream enable + 14 + 1 + + + UDRDET + Detection of underrun condition at slave + transmitter + 11 + 2 + + + UDRCFG + Behavior of slave transmitter at + underrun condition + 9 + 2 + + + FTHVL + threshold level + 5 + 4 + + + DSIZE + Number of bits in at single SPI data + frame + 0 + 5 + + + + + CFG2 + CFG2 + configuration register 2 + 0xC + 0x20 + read-write + 0x00000000 + + + AFCNTR + Alternate function GPIOs + control + 31 + 1 + + + SSOM + SS output management in master + mode + 30 + 1 + + + SSOE + SS output enable + 29 + 1 + + + SSIOP + SS input/output polarity + 28 + 1 + + + SSM + Software management of SS signal + input + 26 + 1 + + + CPOL + Clock polarity + 25 + 1 + + + CPHA + Clock phase + 24 + 1 + + + LSBFRST + Data frame format + 23 + 1 + + + MASTER + SPI Master + 22 + 1 + + + SP + Serial Protocol + 19 + 3 + + + COMM + SPI Communication Mode + 17 + 2 + + + IOSWP + Swap functionality of MISO and MOSI + pins + 15 + 1 + + + MIDI + Master Inter-Data Idleness + 4 + 4 + + + MSSI + Master SS Idleness + 0 + 4 + + + + + IER + IER + Interrupt Enable Register + 0x10 + 0x20 + 0x00000000 + + + TSERFIE + Additional number of transactions reload + interrupt enable + 10 + 1 + read-write + + + MODFIE + Mode Fault interrupt + enable + 9 + 1 + read-write + + + TIFREIE + TIFRE interrupt enable + 8 + 1 + read-write + + + CRCEIE + CRC Interrupt enable + 7 + 1 + read-write + + + OVRIE + OVR interrupt enable + 6 + 1 + read-write + + + UDRIE + UDR interrupt enable + 5 + 1 + read-write + + + TXTFIE + TXTFIE interrupt enable + 4 + 1 + read-write + + + EOTIE + EOT, SUSP and TXC interrupt + enable + 3 + 1 + read-write + + + DPXPIE + DXP interrupt enabled + 2 + 1 + read-only + + + TXPIE + TXP interrupt enable + 1 + 1 + read-only + + + RXPIE + RXP Interrupt Enable + 0 + 1 + read-write + + + + + SR + SR + Status Register + 0x14 + 0x20 + read-only + 0x00001002 + + + CTSIZE + Number of data frames remaining in + current TSIZE session + 16 + 16 + + + RXWNE + RxFIFO Word Not Empty + 15 + 1 + + + RXPLVL + RxFIFO Packing LeVeL + 13 + 2 + + + TXC + TxFIFO transmission + complete + 12 + 1 + + + SUSP + SUSPend + 11 + 1 + + + TSERF + Additional number of SPI data to be + transacted was reload + 10 + 1 + + + MODF + Mode Fault + 9 + 1 + + + TIFRE + TI frame format error + 8 + 1 + + + CRCE + CRC Error + 7 + 1 + + + OVR + Overrun + 6 + 1 + + + UDR + Underrun at slave transmission + mode + 5 + 1 + + + TXTF + Transmission Transfer + Filled + 4 + 1 + + + EOT + End Of Transfer + 3 + 1 + + + DXP + Duplex Packet + 2 + 1 + + + TXP + Tx-Packet space available + 1 + 1 + + + RXP + Rx-Packet available + 0 + 1 + + + + + IFCR + IFCR + Interrupt/Status Flags Clear + Register + 0x18 + 0x20 + write-only + 0x00000000 + + + SUSPC + SUSPend flag clear + 11 + 1 + + + TSERFC + TSERFC flag clear + 10 + 1 + + + MODFC + Mode Fault flag clear + 9 + 1 + + + TIFREC + TI frame format error flag + clear + 8 + 1 + + + CRCEC + CRC Error flag clear + 7 + 1 + + + OVRC + Overrun flag clear + 6 + 1 + + + UDRC + Underrun flag clear + 5 + 1 + + + TXTFC + Transmission Transfer Filled flag + clear + 4 + 1 + + + EOTC + End Of Transfer flag clear + 3 + 1 + + + + + TXDR + TXDR + Transmit Data Register + 0x20 + 0x20 + write-only + 0x00000000 + + + TXDR + Transmit data register + 0 + 32 + + + + + RXDR + RXDR + Receive Data Register + 0x30 + 0x20 + read-only + 0x00000000 + + + RXDR + Receive data register + 0 + 32 + + + + + CRCPOLY + CRCPOLY + Polynomial Register + 0x40 + 0x20 + read-write + 0x00000107 + + + CRCPOLY + CRC polynomial register + 0 + 32 + + + + + TXCRC + TXCRC + Transmitter CRC Register + 0x44 + 0x20 + read-write + 0x00000000 + + + TXCRC + CRC register for + transmitter + 0 + 32 + + + + + RXCRC + RXCRC + Receiver CRC Register + 0x48 + 0x20 + read-write + 0x00000000 + + + RXCRC + CRC register for receiver + 0 + 32 + + + + + UDRDR + UDRDR + Underrun Data Register + 0x4C + 0x20 + read-write + 0x00000000 + + + UDRDR + Data at slave underrun + condition + 0 + 32 + + + + + CGFR + CGFR + configuration register + 0x50 + 0x20 + read-write + 0x00000000 + + + MCKOE + Master clock output enable + 25 + 1 + + + ODD + Odd factor for the + prescaler + 24 + 1 + + + I2SDIV + I2S linear prescaler + 16 + 8 + + + DATFMT + Data format + 14 + 1 + + + WSINV + Fixed channel length in + SLAVE + 13 + 1 + + + FIXCH + Word select inversion + 12 + 1 + + + CKPOL + Serial audio clock + polarity + 11 + 1 + + + CHLEN + Channel length (number of bits per audio + channel) + 10 + 1 + + + DATLEN + Data length to be + transferred + 8 + 2 + + + PCMSYNC + PCM frame synchronization + 7 + 1 + + + I2SSTD + I2S standard selection + 4 + 2 + + + I2SCFG + I2S configuration mode + 1 + 3 + + + I2SMOD + I2S mode selection + 0 + 1 + + + + + + + SPI2 + 0x40003800 + + SPI2 + SPI2 global interrupt + 36 + + + + SPI3 + 0x40003C00 + + SPI3 + SPI3 global interrupt + 51 + + + + SPI4 + 0x40013400 + + SPI4 + SPI4 global interrupt + 84 + + + + SPI5 + 0x40015000 + + SPI5 + SPI5 global interrupt + 85 + + + + SPI6 + 0x58001400 + + SPI6 + SPI6 global interrupt + 86 + + + + LTDC + LCD-TFT Controller + LTDC + 0x50001000 + + 0x0 + 0x1000 + registers + + + LTDC + LCD-TFT global interrupt + 88 + + + LTDC_ER + LCD-TFT error interrupt + 89 + + + + SSCR + SSCR + Synchronization Size Configuration + Register + 0x8 + 0x20 + read-write + 0x00000000 + + + HSW + Horizontal Synchronization Width (in + units of pixel clock period) + 16 + 10 + + + VSH + Vertical Synchronization Height (in + units of horizontal scan line) + 0 + 11 + + + + + BPCR + BPCR + Back Porch Configuration + Register + 0xC + 0x20 + read-write + 0x00000000 + + + AHBP + Accumulated Horizontal back porch (in + units of pixel clock period) + 16 + 12 + + + AVBP + Accumulated Vertical back porch (in + units of horizontal scan line) + 0 + 11 + + + + + AWCR + AWCR + Active Width Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + AAV + AAV + 16 + 12 + + + AAH + Accumulated Active Height (in units of + horizontal scan line) + 0 + 11 + + + + + TWCR + TWCR + Total Width Configuration + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + TOTALW + Total Width (in units of pixel clock + period) + 16 + 12 + + + TOTALH + Total Height (in units of horizontal + scan line) + 0 + 11 + + + + + GCR + GCR + Global Control Register + 0x18 + 0x20 + 0x00002220 + + + HSPOL + Horizontal Synchronization + Polarity + 31 + 1 + read-write + + + VSPOL + Vertical Synchronization + Polarity + 30 + 1 + read-write + + + DEPOL + Data Enable Polarity + 29 + 1 + read-write + + + PCPOL + Pixel Clock Polarity + 28 + 1 + read-write + + + DEN + Dither Enable + 16 + 1 + read-write + + + DRW + Dither Red Width + 12 + 3 + read-only + + + DGW + Dither Green Width + 8 + 3 + read-only + + + DBW + Dither Blue Width + 4 + 3 + read-only + + + LTDCEN + LCD-TFT controller enable + bit + 0 + 1 + read-write + + + + + SRCR + SRCR + Shadow Reload Configuration + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + VBR + Vertical Blanking Reload + 1 + 1 + + + IMR + Immediate Reload + 0 + 1 + + + + + BCCR + BCCR + Background Color Configuration + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BCBLUE + Background Color Blue + value + 0 + 8 + + + BCGREEN + Background Color Green + value + 8 + 8 + + + BCRED + Background Color Red value + 16 + 8 + + + + + IER + IER + Interrupt Enable Register + 0x34 + 0x20 + read-write + 0x00000000 + + + RRIE + Register Reload interrupt + enable + 3 + 1 + + + TERRIE + Transfer Error Interrupt + Enable + 2 + 1 + + + FUIE + FIFO Underrun Interrupt + Enable + 1 + 1 + + + LIE + Line Interrupt Enable + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x38 + 0x20 + read-only + 0x00000000 + + + RRIF + Register Reload Interrupt + Flag + 3 + 1 + + + TERRIF + Transfer Error interrupt + flag + 2 + 1 + + + FUIF + FIFO Underrun Interrupt + flag + 1 + 1 + + + LIF + Line Interrupt flag + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x3C + 0x20 + write-only + 0x00000000 + + + CRRIF + Clears Register Reload Interrupt + Flag + 3 + 1 + + + CTERRIF + Clears the Transfer Error Interrupt + Flag + 2 + 1 + + + CFUIF + Clears the FIFO Underrun Interrupt + flag + 1 + 1 + + + CLIF + Clears the Line Interrupt + Flag + 0 + 1 + + + + + LIPCR + LIPCR + Line Interrupt Position Configuration + Register + 0x40 + 0x20 + read-write + 0x00000000 + + + LIPOS + Line Interrupt Position + 0 + 11 + + + + + CPSR + CPSR + Current Position Status + Register + 0x44 + 0x20 + read-only + 0x00000000 + + + CXPOS + Current X Position + 16 + 16 + + + CYPOS + Current Y Position + 0 + 16 + + + + + CDSR + CDSR + Current Display Status + Register + 0x48 + 0x20 + read-only + 0x0000000F + + + HSYNCS + Horizontal Synchronization display + Status + 3 + 1 + + + VSYNCS + Vertical Synchronization display + Status + 2 + 1 + + + HDES + Horizontal Data Enable display + Status + 1 + 1 + + + VDES + Vertical Data Enable display + Status + 0 + 1 + + + + + L1CR + L1CR + Layerx Control Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L1WHPCR + L1WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x88 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L1WVPCR + L1WVPCR + Layerx Window Vertical Position + Configuration Register + 0x8C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L1CKCR + L1CKCR + Layerx Color Keying Configuration + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L1PFCR + L1PFCR + Layerx Pixel Format Configuration + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L1CACR + L1CACR + Layerx Constant Alpha Configuration + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L1DCCR + L1DCCR + Layerx Default Color Configuration + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L1BFCR + L1BFCR + Layerx Blending Factors Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L1CFBAR + L1CFBAR + Layerx Color Frame Buffer Address + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L1CFBLR + L1CFBLR + Layerx Color Frame Buffer Length + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L1CFBLNR + L1CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L1CLUTWR + L1CLUTWR + Layerx CLUT Write Register + 0xC4 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + L2CR + L2CR + Layerx Control Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CLUTEN + Color Look-Up Table Enable + 4 + 1 + + + COLKEN + Color Keying Enable + 1 + 1 + + + LEN + Layer Enable + 0 + 1 + + + + + L2WHPCR + L2WHPCR + Layerx Window Horizontal Position + Configuration Register + 0x108 + 0x20 + read-write + 0x00000000 + + + WHSPPOS + Window Horizontal Stop + Position + 16 + 12 + + + WHSTPOS + Window Horizontal Start + Position + 0 + 12 + + + + + L2WVPCR + L2WVPCR + Layerx Window Vertical Position + Configuration Register + 0x10C + 0x20 + read-write + 0x00000000 + + + WVSPPOS + Window Vertical Stop + Position + 16 + 11 + + + WVSTPOS + Window Vertical Start + Position + 0 + 11 + + + + + L2CKCR + L2CKCR + Layerx Color Keying Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + CKRED + Color Key Red value + 16 + 8 + + + CKGREEN + Color Key Green value + 8 + 8 + + + CKBLUE + Color Key Blue value + 0 + 8 + + + + + L2PFCR + L2PFCR + Layerx Pixel Format Configuration + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + PF + Pixel Format + 0 + 3 + + + + + L2CACR + L2CACR + Layerx Constant Alpha Configuration + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + CONSTA + Constant Alpha + 0 + 8 + + + + + L2DCCR + L2DCCR + Layerx Default Color Configuration + Register + 0x11C + 0x20 + read-write + 0x00000000 + + + DCALPHA + Default Color Alpha + 24 + 8 + + + DCRED + Default Color Red + 16 + 8 + + + DCGREEN + Default Color Green + 8 + 8 + + + DCBLUE + Default Color Blue + 0 + 8 + + + + + L2BFCR + L2BFCR + Layerx Blending Factors Configuration + Register + 0x120 + 0x20 + read-write + 0x00000607 + + + BF1 + Blending Factor 1 + 8 + 3 + + + BF2 + Blending Factor 2 + 0 + 3 + + + + + L2CFBAR + L2CFBAR + Layerx Color Frame Buffer Address + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + CFBADD + Color Frame Buffer Start + Address + 0 + 32 + + + + + L2CFBLR + L2CFBLR + Layerx Color Frame Buffer Length + Register + 0x130 + 0x20 + read-write + 0x00000000 + + + CFBP + Color Frame Buffer Pitch in + bytes + 16 + 13 + + + CFBLL + Color Frame Buffer Line + Length + 0 + 13 + + + + + L2CFBLNR + L2CFBLNR + Layerx ColorFrame Buffer Line Number + Register + 0x134 + 0x20 + read-write + 0x00000000 + + + CFBLNBR + Frame Buffer Line Number + 0 + 11 + + + + + L2CLUTWR + L2CLUTWR + Layerx CLUT Write Register + 0x144 + 0x20 + write-only + 0x00000000 + + + CLUTADD + CLUT Address + 24 + 8 + + + RED + Red value + 16 + 8 + + + GREEN + Green value + 8 + 8 + + + BLUE + Blue value + 0 + 8 + + + + + + + SPDIFRX + Receiver Interface + SPDIFRX + 0x40004000 + + 0x0 + 0x400 + registers + + + SPDIF + SPDIFRX global interrupt + 97 + + + + CR + CR + Control register + 0x0 + 0x20 + read-write + 0x00000000 + + + SPDIFRXEN + Peripheral Block Enable + 0 + 2 + + + RXDMAEN + Receiver DMA ENable for data + flow + 2 + 1 + + + RXSTEO + STerEO Mode + 3 + 1 + + + DRFMT + RX Data format + 4 + 2 + + + PMSK + Mask Parity error bit + 6 + 1 + + + VMSK + Mask of Validity bit + 7 + 1 + + + CUMSK + Mask of channel status and user + bits + 8 + 1 + + + PTMSK + Mask of Preamble Type bits + 9 + 1 + + + CBDMAEN + Control Buffer DMA ENable for control + flow + 10 + 1 + + + CHSEL + Channel Selection + 11 + 1 + + + NBTR + Maximum allowed re-tries during + synchronization phase + 12 + 2 + + + WFA + Wait For Activity + 14 + 1 + + + INSEL + input selection + 16 + 3 + + + CKSEN + Symbol Clock Enable + 20 + 1 + + + CKSBKPEN + Backup Symbol Clock Enable + 21 + 1 + + + + + IMR + IMR + Interrupt mask register + 0x4 + 0x20 + read-write + 0x00000000 + + + RXNEIE + RXNE interrupt enable + 0 + 1 + + + CSRNEIE + Control Buffer Ready Interrupt + Enable + 1 + 1 + + + PERRIE + Parity error interrupt + enable + 2 + 1 + + + OVRIE + Overrun error Interrupt + Enable + 3 + 1 + + + SBLKIE + Synchronization Block Detected Interrupt + Enable + 4 + 1 + + + SYNCDIE + Synchronization Done + 5 + 1 + + + IFEIE + Serial Interface Error Interrupt + Enable + 6 + 1 + + + + + SR + SR + Status register + 0x8 + 0x20 + read-only + 0x00000000 + + + RXNE + Read data register not + empty + 0 + 1 + + + CSRNE + Control Buffer register is not + empty + 1 + 1 + + + PERR + Parity error + 2 + 1 + + + OVR + Overrun error + 3 + 1 + + + SBD + Synchronization Block + Detected + 4 + 1 + + + SYNCD + Synchronization Done + 5 + 1 + + + FERR + Framing error + 6 + 1 + + + SERR + Synchronization error + 7 + 1 + + + TERR + Time-out error + 8 + 1 + + + WIDTH5 + Duration of 5 symbols counted with + SPDIF_CLK + 16 + 15 + + + + + IFCR + IFCR + Interrupt Flag Clear register + 0xC + 0x20 + write-only + 0x00000000 + + + PERRCF + Clears the Parity error + flag + 2 + 1 + + + OVRCF + Clears the Overrun error + flag + 3 + 1 + + + SBDCF + Clears the Synchronization Block + Detected flag + 4 + 1 + + + SYNCDCF + Clears the Synchronization Done + flag + 5 + 1 + + + + + DR_00 + DR_00 + Data input register + 0x10 + 0x20 + read-only + 0x00000000 + + + DR + Parity Error bit + 0 + 24 + + + PE + Parity Error bit + 24 + 1 + + + V + Validity bit + 25 + 1 + + + U + User bit + 26 + 1 + + + C + Channel Status bit + 27 + 1 + + + PT + Preamble Type + 28 + 2 + + + + + CSR + CSR + Channel Status register + 0x14 + 0x20 + read-only + 0x00000000 + + + USR + User data information + 0 + 16 + + + CS + Channel A status + information + 16 + 8 + + + SOB + Start Of Block + 24 + 1 + + + + + DIR + DIR + Debug Information register + 0x18 + 0x20 + read-only + 0x00000000 + + + THI + Threshold HIGH + 0 + 13 + + + TLO + Threshold LOW + 16 + 13 + + + + + VERR + VERR + SPDIFRX version register + 0x3F4 + 0x20 + read-only + 0x00000012 + + + MINREV + Minor revision + 0 + 4 + + + MAJREV + Major revision + 4 + 4 + + + + + IDR + IDR + SPDIFRX identification + register + 0x3F8 + 0x20 + read-only + 0x00130041 + + + ID + SPDIFRX identifier + 0 + 32 + + + + + SIDR + SIDR + SPDIFRX size identification + register + 0x3FC + 0x20 + read-only + 0xA3C5DD01 + + + SID + Size identification + 0 + 32 + + + + + DR_01 + DR_01 + Data input register + DR_00 + 0x10 + 0x20 + read-only + 0x00000000 + + + PE + Parity Error bit + 0 + 1 + + + V + Validity bit + 1 + 1 + + + U + User bit + 2 + 1 + + + C + Channel Status bit + 3 + 1 + + + PT + Preamble Type + 4 + 2 + + + DR + Data value + 8 + 24 + + + + + DR_10 + DR_10 + Data input register + DR_00 + 0x10 + 0x20 + read-only + 0x00000000 + + + DRNL1 + Data value + 0 + 16 + + + DRNL2 + Data value + 16 + 16 + + + + + + + ADC3 + Analog to Digital Converter + ADC + 0x58026000 + + 0x0 + 0xD1 + registers + + + ADC3 + ADC3 global interrupt + 127 + + + + ISR + ISR + ADC interrupt and status + register + 0x0 + 0x20 + read-write + 0x00000000 + + + JQOVF + ADC group injected contexts queue + overflow flag + 10 + 1 + + + AWD3 + ADC analog watchdog 3 flag + 9 + 1 + + + AWD2 + ADC analog watchdog 2 flag + 8 + 1 + + + AWD1 + ADC analog watchdog 1 flag + 7 + 1 + + + JEOS + ADC group injected end of sequence + conversions flag + 6 + 1 + + + JEOC + ADC group injected end of unitary + conversion flag + 5 + 1 + + + OVR + ADC group regular overrun + flag + 4 + 1 + + + EOS + ADC group regular end of sequence + conversions flag + 3 + 1 + + + EOC + ADC group regular end of unitary + conversion flag + 2 + 1 + + + EOSMP + ADC group regular end of sampling + flag + 1 + 1 + + + ADRDY + ADC ready flag + 0 + 1 + + + + + IER + IER + ADC interrupt enable register + 0x4 + 0x20 + read-write + 0x00000000 + + + JQOVFIE + ADC group injected contexts queue + overflow interrupt + 10 + 1 + + + AWD3IE + ADC analog watchdog 3 + interrupt + 9 + 1 + + + AWD2IE + ADC analog watchdog 2 + interrupt + 8 + 1 + + + AWD1IE + ADC analog watchdog 1 + interrupt + 7 + 1 + + + JEOSIE + ADC group injected end of sequence + conversions interrupt + 6 + 1 + + + JEOCIE + ADC group injected end of unitary + conversion interrupt + 5 + 1 + + + OVRIE + ADC group regular overrun + interrupt + 4 + 1 + + + EOSIE + ADC group regular end of sequence + conversions interrupt + 3 + 1 + + + EOCIE + ADC group regular end of unitary + conversion interrupt + 2 + 1 + + + EOSMPIE + ADC group regular end of sampling + interrupt + 1 + 1 + + + ADRDYIE + ADC ready interrupt + 0 + 1 + + + + + CR + CR + ADC control register + 0x8 + 0x20 + read-write + 0x00000000 + + + ADCAL + ADC calibration + 31 + 1 + + + ADCALDIF + ADC differential mode for + calibration + 30 + 1 + + + DEEPPWD + ADC deep power down enable + 29 + 1 + + + ADVREGEN + ADC voltage regulator + enable + 28 + 1 + + + LINCALRDYW6 + Linearity calibration ready Word + 6 + 27 + 1 + + + LINCALRDYW5 + Linearity calibration ready Word + 5 + 26 + 1 + + + LINCALRDYW4 + Linearity calibration ready Word + 4 + 25 + 1 + + + LINCALRDYW3 + Linearity calibration ready Word + 3 + 24 + 1 + + + LINCALRDYW2 + Linearity calibration ready Word + 2 + 23 + 1 + + + LINCALRDYW1 + Linearity calibration ready Word + 1 + 22 + 1 + + + ADCALLIN + Linearity calibration + 16 + 1 + + + BOOST + Boost mode control + 8 + 1 + + + JADSTP + ADC group injected conversion + stop + 5 + 1 + + + ADSTP + ADC group regular conversion + stop + 4 + 1 + + + JADSTART + ADC group injected conversion + start + 3 + 1 + + + ADSTART + ADC group regular conversion + start + 2 + 1 + + + ADDIS + ADC disable + 1 + 1 + + + ADEN + ADC enable + 0 + 1 + + + + + CFGR + CFGR + ADC configuration register 1 + 0xC + 0x20 + read-write + 0x00000000 + + + JQDIS + ADC group injected contexts queue + disable + 31 + 1 + + + AWDCH1CH + ADC analog watchdog 1 monitored channel + selection + 26 + 5 + + + JAUTO + ADC group injected automatic trigger + mode + 25 + 1 + + + JAWD1EN + ADC analog watchdog 1 enable on scope + ADC group injected + 24 + 1 + + + AWD1EN + ADC analog watchdog 1 enable on scope + ADC group regular + 23 + 1 + + + AWD1SGL + ADC analog watchdog 1 monitoring a + single channel or all channels + 22 + 1 + + + JQM + ADC group injected contexts queue + mode + 21 + 1 + + + JDISCEN + ADC group injected sequencer + discontinuous mode + 20 + 1 + + + DISCNUM + ADC group regular sequencer + discontinuous number of ranks + 17 + 3 + + + DISCEN + ADC group regular sequencer + discontinuous mode + 16 + 1 + + + AUTDLY + ADC low power auto wait + 14 + 1 + + + CONT + ADC group regular continuous conversion + mode + 13 + 1 + + + OVRMOD + ADC group regular overrun + configuration + 12 + 1 + + + EXTEN + ADC group regular external trigger + polarity + 10 + 2 + + + EXTSEL + ADC group regular external trigger + source + 5 + 5 + + + RES + ADC data resolution + 2 + 3 + + + DMNGT + ADC DMA transfer enable + 0 + 2 + + + + + CFGR2 + CFGR2 + ADC configuration register 2 + 0x10 + 0x20 + read-write + 0x00000000 + + + ROVSE + ADC oversampler enable on scope ADC + group regular + 0 + 1 + + + JOVSE + ADC oversampler enable on scope ADC + group injected + 1 + 1 + + + OVSS + ADC oversampling shift + 5 + 4 + + + TROVS + ADC oversampling discontinuous mode + (triggered mode) for ADC group regular + 9 + 1 + + + ROVSM + Regular Oversampling mode + 10 + 1 + + + RSHIFT1 + Right-shift data after Offset 1 + correction + 11 + 1 + + + RSHIFT2 + Right-shift data after Offset 2 + correction + 12 + 1 + + + RSHIFT3 + Right-shift data after Offset 3 + correction + 13 + 1 + + + RSHIFT4 + Right-shift data after Offset 4 + correction + 14 + 1 + + + OSR + Oversampling ratio + 16 + 10 + + + LSHIFT + Left shift factor + 28 + 4 + + + + + SMPR1 + SMPR1 + ADC sampling time register 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + SMP9 + ADC channel 9 sampling time + selection + 27 + 3 + + + SMP8 + ADC channel 8 sampling time + selection + 24 + 3 + + + SMP7 + ADC channel 7 sampling time + selection + 21 + 3 + + + SMP6 + ADC channel 6 sampling time + selection + 18 + 3 + + + SMP5 + ADC channel 5 sampling time + selection + 15 + 3 + + + SMP4 + ADC channel 4 sampling time + selection + 12 + 3 + + + SMP3 + ADC channel 3 sampling time + selection + 9 + 3 + + + SMP2 + ADC channel 2 sampling time + selection + 6 + 3 + + + SMP1 + ADC channel 1 sampling time + selection + 3 + 3 + + + + + SMPR2 + SMPR2 + ADC sampling time register 2 + 0x18 + 0x20 + read-write + 0x00000000 + + + SMP19 + ADC channel 18 sampling time + selection + 27 + 3 + + + SMP18 + ADC channel 18 sampling time + selection + 24 + 3 + + + SMP17 + ADC channel 17 sampling time + selection + 21 + 3 + + + SMP16 + ADC channel 16 sampling time + selection + 18 + 3 + + + SMP15 + ADC channel 15 sampling time + selection + 15 + 3 + + + SMP14 + ADC channel 14 sampling time + selection + 12 + 3 + + + SMP13 + ADC channel 13 sampling time + selection + 9 + 3 + + + SMP12 + ADC channel 12 sampling time + selection + 6 + 3 + + + SMP11 + ADC channel 11 sampling time + selection + 3 + 3 + + + SMP10 + ADC channel 10 sampling time + selection + 0 + 3 + + + + + LTR1 + LTR1 + ADC analog watchdog 1 threshold + register + 0x20 + 0x20 + read-write + 0x0FFF0000 + + + LTR1 + ADC analog watchdog 1 threshold + low + 0 + 26 + + + + + LHTR1 + LHTR1 + ADC analog watchdog 2 threshold + register + 0x24 + 0x20 + read-write + 0x0FFF0000 + + + LHTR1 + ADC analog watchdog 2 threshold + low + 0 + 26 + + + + + SQR1 + SQR1 + ADC group regular sequencer ranks register + 1 + 0x30 + 0x20 + read-write + 0x00000000 + + + SQ4 + ADC group regular sequencer rank + 4 + 24 + 5 + + + SQ3 + ADC group regular sequencer rank + 3 + 18 + 5 + + + SQ2 + ADC group regular sequencer rank + 2 + 12 + 5 + + + SQ1 + ADC group regular sequencer rank + 1 + 6 + 5 + + + L3 + L3 + 0 + 4 + + + + + SQR2 + SQR2 + ADC group regular sequencer ranks register + 2 + 0x34 + 0x20 + read-write + 0x00000000 + + + SQ9 + ADC group regular sequencer rank + 9 + 24 + 5 + + + SQ8 + ADC group regular sequencer rank + 8 + 18 + 5 + + + SQ7 + ADC group regular sequencer rank + 7 + 12 + 5 + + + SQ6 + ADC group regular sequencer rank + 6 + 6 + 5 + + + SQ5 + ADC group regular sequencer rank + 5 + 0 + 5 + + + + + SQR3 + SQR3 + ADC group regular sequencer ranks register + 3 + 0x38 + 0x20 + read-write + 0x00000000 + + + SQ14 + ADC group regular sequencer rank + 14 + 24 + 5 + + + SQ13 + ADC group regular sequencer rank + 13 + 18 + 5 + + + SQ12 + ADC group regular sequencer rank + 12 + 12 + 5 + + + SQ11 + ADC group regular sequencer rank + 11 + 6 + 5 + + + SQ10 + ADC group regular sequencer rank + 10 + 0 + 5 + + + + + SQR4 + SQR4 + ADC group regular sequencer ranks register + 4 + 0x3C + 0x20 + read-write + 0x00000000 + + + SQ16 + ADC group regular sequencer rank + 16 + 6 + 5 + + + SQ15 + ADC group regular sequencer rank + 15 + 0 + 5 + + + + + DR + DR + ADC group regular conversion data + register + 0x40 + 0x20 + read-only + 0x00000000 + + + RDATA + ADC group regular conversion + data + 0 + 16 + + + + + JSQR + JSQR + ADC group injected sequencer + register + 0x4C + 0x20 + read-write + 0x00000000 + + + JSQ4 + ADC group injected sequencer rank + 4 + 27 + 5 + + + JSQ3 + ADC group injected sequencer rank + 3 + 21 + 5 + + + JSQ2 + ADC group injected sequencer rank + 2 + 15 + 5 + + + JSQ1 + ADC group injected sequencer rank + 1 + 9 + 5 + + + JEXTEN + ADC group injected external trigger + polarity + 7 + 2 + + + JEXTSEL + ADC group injected external trigger + source + 2 + 5 + + + JL + ADC group injected sequencer scan + length + 0 + 2 + + + + + OFR1 + OFR1 + ADC offset number 1 register + 0x60 + 0x20 + read-write + 0x00000000 + + + SSATE + ADC offset number 1 enable + 31 + 1 + + + OFFSET1_CH + ADC offset number 1 channel + selection + 26 + 5 + + + OFFSET1 + ADC offset number 1 offset + level + 0 + 26 + + + + + OFR2 + OFR2 + ADC offset number 2 register + 0x64 + 0x20 + read-write + 0x00000000 + + + SSATE + ADC offset number 1 enable + 31 + 1 + + + OFFSET1_CH + ADC offset number 1 channel + selection + 26 + 5 + + + OFFSET1 + ADC offset number 1 offset + level + 0 + 26 + + + + + OFR3 + OFR3 + ADC offset number 3 register + 0x68 + 0x20 + read-write + 0x00000000 + + + SSATE + ADC offset number 1 enable + 31 + 1 + + + OFFSET1_CH + ADC offset number 1 channel + selection + 26 + 5 + + + OFFSET1 + ADC offset number 1 offset + level + 0 + 26 + + + + + OFR4 + OFR4 + ADC offset number 4 register + 0x6C + 0x20 + read-write + 0x00000000 + + + SSATE + ADC offset number 1 enable + 31 + 1 + + + OFFSET1_CH + ADC offset number 1 channel + selection + 26 + 5 + + + OFFSET1 + ADC offset number 1 offset + level + 0 + 26 + + + + + JDR1 + JDR1 + ADC group injected sequencer rank 1 + register + 0x80 + 0x20 + read-only + 0x00000000 + + + JDATA1 + ADC group injected sequencer rank 1 + conversion data + 0 + 32 + + + + + JDR2 + JDR2 + ADC group injected sequencer rank 2 + register + 0x84 + 0x20 + read-only + 0x00000000 + + + JDATA2 + ADC group injected sequencer rank 2 + conversion data + 0 + 32 + + + + + JDR3 + JDR3 + ADC group injected sequencer rank 3 + register + 0x88 + 0x20 + read-only + 0x00000000 + + + JDATA3 + ADC group injected sequencer rank 3 + conversion data + 0 + 32 + + + + + JDR4 + JDR4 + ADC group injected sequencer rank 4 + register + 0x8C + 0x20 + read-only + 0x00000000 + + + JDATA4 + ADC group injected sequencer rank 4 + conversion data + 0 + 32 + + + + + AWD2CR + AWD2CR + ADC analog watchdog 2 configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + AWD2CH + ADC analog watchdog 2 monitored channel + selection + 0 + 20 + + + + + AWD3CR + AWD3CR + ADC analog watchdog 3 configuration + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + AWD3CH + ADC analog watchdog 3 monitored channel + selection + 1 + 20 + + + + + DIFSEL + DIFSEL + ADC channel differential or single-ended + mode selection register + 0xC0 + 0x20 + read-write + 0x00000000 + + + DIFSEL + ADC channel differential or single-ended + mode for channel + 0 + 20 + + + + + CALFACT + CALFACT + ADC calibration factors + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + CALFACT_D + ADC calibration factor in differential + mode + 16 + 11 + + + CALFACT_S + ADC calibration factor in single-ended + mode + 0 + 11 + + + + + PCSEL + PCSEL + ADC pre channel selection + register + 0x1C + 0x20 + read-write + 0x00000000 + + + PCSEL + Channel x (VINP[i]) pre + selection + 0 + 20 + + + + + LTR2 + LTR2 + ADC watchdog lower threshold register + 2 + 0xB0 + 0x20 + read-write + 0x00000000 + + + LTR2 + Analog watchdog 2 lower + threshold + 0 + 26 + + + + + HTR2 + HTR2 + ADC watchdog higher threshold register + 2 + 0xB4 + 0x20 + read-write + 0x00000000 + + + HTR2 + Analog watchdog 2 higher + threshold + 0 + 26 + + + + + LTR3 + LTR3 + ADC watchdog lower threshold register + 3 + 0xB8 + 0x20 + read-write + 0x00000000 + + + LTR3 + Analog watchdog 3 lower + threshold + 0 + 26 + + + + + HTR3 + HTR3 + ADC watchdog higher threshold register + 3 + 0xBC + 0x20 + read-write + 0x00000000 + + + HTR3 + Analog watchdog 3 higher + threshold + 0 + 26 + + + + + CALFACT2 + CALFACT2 + ADC Calibration Factor register + 2 + 0xC8 + 0x20 + read-write + 0x00000000 + + + LINCALFACT + Linearity Calibration + Factor + 0 + 30 + + + + + + + ADC1 + 0x40022000 + + + ADC2 + 0x40022100 + + + ADC3_Common + Analog-to-Digital Converter + ADC + 0x58026300 + + 0x0 + 0x100 + registers + + + + CSR + CSR + ADC Common status register + 0x0 + 0x20 + read-only + 0x00000000 + + + ADRDY_MST + Master ADC ready + 0 + 1 + + + EOSMP_MST + End of Sampling phase flag of the master + ADC + 1 + 1 + + + EOC_MST + End of regular conversion of the master + ADC + 2 + 1 + + + EOS_MST + End of regular sequence flag of the + master ADC + 3 + 1 + + + OVR_MST + Overrun flag of the master + ADC + 4 + 1 + + + JEOC_MST + End of injected conversion flag of the + master ADC + 5 + 1 + + + JEOS_MST + End of injected sequence flag of the + master ADC + 6 + 1 + + + AWD1_MST + Analog watchdog 1 flag of the master + ADC + 7 + 1 + + + AWD2_MST + Analog watchdog 2 flag of the master + ADC + 8 + 1 + + + AWD3_MST + Analog watchdog 3 flag of the master + ADC + 9 + 1 + + + JQOVF_MST + Injected Context Queue Overflow flag of + the master ADC + 10 + 1 + + + ADRDY_SLV + Slave ADC ready + 16 + 1 + + + EOSMP_SLV + End of Sampling phase flag of the slave + ADC + 17 + 1 + + + EOC_SLV + End of regular conversion of the slave + ADC + 18 + 1 + + + EOS_SLV + End of regular sequence flag of the + slave ADC + 19 + 1 + + + OVR_SLV + Overrun flag of the slave + ADC + 20 + 1 + + + JEOC_SLV + End of injected conversion flag of the + slave ADC + 21 + 1 + + + JEOS_SLV + End of injected sequence flag of the + slave ADC + 22 + 1 + + + AWD1_SLV + Analog watchdog 1 flag of the slave + ADC + 23 + 1 + + + AWD2_SLV + Analog watchdog 2 flag of the slave + ADC + 24 + 1 + + + AWD3_SLV + Analog watchdog 3 flag of the slave + ADC + 25 + 1 + + + JQOVF_SLV + Injected Context Queue Overflow flag of + the slave ADC + 26 + 1 + + + + + CCR + CCR + ADC common control register + 0x8 + 0x20 + read-write + 0x00000000 + + + DUAL + Dual ADC mode selection + 0 + 5 + + + DELAY + Delay between 2 sampling + phases + 8 + 4 + + + DAMDF + Dual ADC Mode Data Format + 14 + 2 + + + CKMODE + ADC clock mode + 16 + 2 + + + PRESC + ADC prescaler + 18 + 4 + + + VREFEN + VREFINT enable + 22 + 1 + + + VSENSEEN + Temperature sensor enable + 23 + 1 + + + VBATEN + VBAT enable + 24 + 1 + + + + + CDR + CDR + ADC common regular data register for dual + and triple modes + 0xC + 0x20 + read-only + 0x00000000 + + + RDATA_SLV + Regular data of the slave + ADC + 16 + 16 + + + RDATA_MST + Regular data of the master + ADC + 0 + 16 + + + + + CDR2 + CDR2 + ADC x common regular data register for + 32-bit dual mode + 0x10 + 0x20 + read-only + 0x00000000 + + + RDATA_ALT + Regular data of the master/slave + alternated ADCs + 0 + 32 + + + + + + + ADC12_Common + 0x40022300 + + ADC1_2 + ADC1 and ADC2 + 18 + + + + DMAMUX1 + DMAMUX + DMAMUX + 0x40020800 + + 0x0 + 0x400 + registers + + + DMAMUX1_OV + DMAMUX1 overrun interrupt + 102 + + + + C0CR + C0CR + DMAMux - DMA request line multiplexer + channel x control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C1CR + C1CR + DMAMux - DMA request line multiplexer + channel x control register + 0x4 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C2CR + C2CR + DMAMux - DMA request line multiplexer + channel x control register + 0x8 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C3CR + C3CR + DMAMux - DMA request line multiplexer + channel x control register + 0xC + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C4CR + C4CR + DMAMux - DMA request line multiplexer + channel x control register + 0x10 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C5CR + C5CR + DMAMux - DMA request line multiplexer + channel x control register + 0x14 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C6CR + C6CR + DMAMux - DMA request line multiplexer + channel x control register + 0x18 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C7CR + C7CR + DMAMux - DMA request line multiplexer + channel x control register + 0x1C + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C8CR + C8CR + DMAMux - DMA request line multiplexer + channel x control register + 0x20 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C9CR + C9CR + DMAMux - DMA request line multiplexer + channel x control register + 0x24 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C10CR + C10CR + DMAMux - DMA request line multiplexer + channel x control register + 0x28 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C11CR + C11CR + DMAMux - DMA request line multiplexer + channel x control register + 0x2C + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C12CR + C12CR + DMAMux - DMA request line multiplexer + channel x control register + 0x30 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C13CR + C13CR + DMAMux - DMA request line multiplexer + channel x control register + 0x34 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C14CR + C14CR + DMAMux - DMA request line multiplexer + channel x control register + 0x38 + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + C15CR + C15CR + DMAMux - DMA request line multiplexer + channel x control register + 0x3C + 0x20 + read-write + 0x00000000 + + + DMAREQ_ID + Input DMA request line + selected + 0 + 8 + + + SOIE + Interrupt enable at synchronization + event overrun + 8 + 1 + + + EGE + Event generation + enable/disable + 9 + 1 + + + SE + Synchronous operating mode + enable/disable + 16 + 1 + + + SPOL + Synchronization event type selector + Defines the synchronization event on the selected + synchronization input: + 17 + 2 + + + NBREQ + Number of DMA requests to forward + Defines the number of DMA requests forwarded before + output event is generated. In synchronous mode, it + also defines the number of DMA requests to forward + after a synchronization event, then stop forwarding. + The actual number of DMA requests forwarded is + NBREQ+1. Note: This field can only be written when + both SE and EGE bits are reset. + 19 + 5 + + + SYNC_ID + Synchronization input + selected + 24 + 5 + + + + + RG0CR + RG0CR + DMAMux - DMA request generator channel x + control register + 0x100 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG1CR + RG1CR + DMAMux - DMA request generator channel x + control register + 0x104 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG2CR + RG2CR + DMAMux - DMA request generator channel x + control register + 0x108 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG3CR + RG3CR + DMAMux - DMA request generator channel x + control register + 0x10C + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG4CR + RG4CR + DMAMux - DMA request generator channel x + control register + 0x110 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG5CR + RG5CR + DMAMux - DMA request generator channel x + control register + 0x114 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG6CR + RG6CR + DMAMux - DMA request generator channel x + control register + 0x118 + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RG7CR + RG7CR + DMAMux - DMA request generator channel x + control register + 0x11C + 0x20 + read-write + 0x00000000 + + + SIG_ID + DMA request trigger input + selected + 0 + 5 + + + OIE + Interrupt enable at trigger event + overrun + 8 + 1 + + + GE + DMA request generator channel + enable/disable + 16 + 1 + + + GPOL + DMA request generator trigger event type + selection Defines the trigger event on the selected + DMA request trigger input + 17 + 2 + + + GNBREQ + Number of DMA requests to generate + Defines the number of DMA requests generated after a + trigger event, then stop generating. The actual + number of generated DMA requests is GNBREQ+1. Note: + This field can only be written when GE bit is + reset. + 19 + 5 + + + + + RGSR + RGSR + DMAMux - DMA request generator status + register + 0x140 + 0x20 + read-only + 0x00000000 + + + OF + Trigger event overrun flag The flag is + set when a trigger event occurs on DMA request + generator channel x, while the DMA request generator + counter value is lower than GNBREQ. The flag is + cleared by writing 1 to the corresponding COFx bit in + DMAMUX_RGCFR register. + 0 + 8 + + + + + RGCFR + RGCFR + DMAMux - DMA request generator clear flag + register + 0x144 + 0x20 + write-only + 0x00000000 + + + COF + Clear trigger event overrun flag Upon + setting, this bit clears the corresponding overrun + flag OFx in the DMAMUX_RGCSR register. + 0 + 8 + + + + + CSR + CSR + DMAMUX request line multiplexer interrupt + channel status register + 0x80 + 0x20 + read-only + 0x00000000 + + + SOF + Synchronization overrun event + flag + 0 + 16 + + + + + CFR + CFR + DMAMUX request line multiplexer interrupt + clear flag register + 0x84 + 0x20 + write-only + 0x00000000 + + + CSOF + Clear synchronization overrun event + flag + 0 + 16 + + + + + + + CRC + Cryptographic processor + CRC + 0x58024C00 + + 0x0 + 0x400 + registers + + + + DR + DR + Data register + 0x0 + 0x20 + read-write + 0xFFFFFFFF + + + DR + Data Register + 0 + 32 + + + + + IDR + IDR + Independent Data register + 0x4 + 0x20 + read-write + 0x00000000 + + + IDR + Independent Data register + 0 + 32 + + + + + CR + CR + Control register + 0x8 + 0x20 + 0x00000000 + + + RESET + RESET bit + 0 + 1 + write-only + + + POLYSIZE + Polynomial size + 3 + 2 + read-write + + + REV_IN + Reverse input data + 5 + 2 + read-write + + + REV_OUT + Reverse output data + 7 + 1 + read-write + + + + + INIT + INIT + Initial CRC value + 0xC + 0x20 + read-write + 0x00000000 + + + CRC_INIT + Programmable initial CRC + value + 0 + 32 + + + + + POL + POL + CRC polynomial + 0x10 + 0x20 + read-write + 0x00000000 + + + POL + Programmable polynomial + 0 + 32 + + + + + + + RCC + Reset and clock control + RCC + 0x58024400 + + 0x0 + 0x400 + registers + + + RCC + RCC global interrupt + 5 + + + + CR + CR + clock control register + 0x0 + 0x20 + read-write + 0x00000083 + + + HSION + Internal high-speed clock + enable + 0 + 1 + + + HSIKERON + High Speed Internal clock enable in Stop + mode + 1 + 1 + + + HSIRDY + HSI clock ready flag + 2 + 1 + + + HSIDIV + HSI clock divider + 3 + 2 + + + HSIDIVF + HSI divider flag + 5 + 1 + + + CSION + CSI clock enable + 7 + 1 + + + CSIRDY + CSI clock ready flag + 8 + 1 + + + CSIKERON + CSI clock enable in Stop + mode + 9 + 1 + + + RC48ON + RC48 clock enable + 12 + 1 + + + RC48RDY + RC48 clock ready flag + 13 + 1 + + + D1CKRDY + D1 domain clocks ready + flag + 14 + 1 + + + D2CKRDY + D2 domain clocks ready + flag + 15 + 1 + + + HSEON + HSE clock enable + 16 + 1 + + + HSERDY + HSE clock ready flag + 17 + 1 + + + HSEBYP + HSE clock bypass + 18 + 1 + + + HSECSSON + HSE Clock Security System + enable + 19 + 1 + + + PLL1ON + PLL1 enable + 24 + 1 + + + PLL1RDY + PLL1 clock ready flag + 25 + 1 + + + PLL2ON + PLL2 enable + 26 + 1 + + + PLL2RDY + PLL2 clock ready flag + 27 + 1 + + + PLL3ON + PLL3 enable + 28 + 1 + + + PLL3RDY + PLL3 clock ready flag + 29 + 1 + + + + + ICSCR + ICSCR + RCC Internal Clock Source Calibration + Register + 0x4 + 0x20 + 0x40000000 + + + HSICAL + HSI clock calibration + 0 + 12 + read-only + + + HSITRIM + HSI clock trimming + 12 + 6 + read-write + + + CSICAL + CSI clock calibration + 18 + 8 + read-only + + + CSITRIM + CSI clock trimming + 26 + 5 + read-write + + + + + CRRCR + CRRCR + RCC Clock Recovery RC Register + 0x8 + 0x20 + read-only + 0x00000000 + + + RC48CAL + Internal RC 48 MHz clock + calibration + 0 + 10 + + + + + CFGR + CFGR + RCC Clock Configuration + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + SW + System clock switch + 0 + 3 + + + SWS + System clock switch status + 3 + 3 + + + STOPWUCK + System clock selection after a wake up + from system Stop + 6 + 1 + + + STOPKERWUCK + Kernel clock selection after a wake up + from system Stop + 7 + 1 + + + RTCPRE + HSE division factor for RTC + clock + 8 + 6 + + + HRTIMSEL + High Resolution Timer clock prescaler + selection + 14 + 1 + + + TIMPRE + Timers clocks prescaler + selection + 15 + 1 + + + MCO1PRE + MCO1 prescaler + 18 + 4 + + + MCO1SEL + Micro-controller clock output + 1 + 22 + 3 + + + MCO2PRE + MCO2 prescaler + 25 + 4 + + + MCO2SEL + Micro-controller clock output + 2 + 29 + 3 + + + + + D1CFGR + D1CFGR + RCC Domain 1 Clock Configuration + Register + 0x18 + 0x20 + read-write + 0x00000000 + + + HPRE + D1 domain AHB prescaler + 0 + 4 + + + D1PPRE + D1 domain APB3 prescaler + 4 + 3 + + + D1CPRE + D1 domain Core prescaler + 8 + 4 + + + + + D2CFGR + D2CFGR + RCC Domain 2 Clock Configuration + Register + 0x1C + 0x20 + read-write + 0x00000000 + + + D2PPRE1 + D2 domain APB1 prescaler + 4 + 3 + + + D2PPRE2 + D2 domain APB2 prescaler + 8 + 3 + + + + + D3CFGR + D3CFGR + RCC Domain 3 Clock Configuration + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + D3PPRE + D3 domain APB4 prescaler + 4 + 3 + + + + + PLLCKSELR + PLLCKSELR + RCC PLLs Clock Source Selection + Register + 0x28 + 0x20 + read-write + 0x02020200 + + + PLLSRC + DIVMx and PLLs clock source + selection + 0 + 2 + + + DIVM1 + Prescaler for PLL1 + 4 + 6 + + + DIVM2 + Prescaler for PLL2 + 12 + 6 + + + DIVM3 + Prescaler for PLL3 + 20 + 6 + + + + + PLLCFGR + PLLCFGR + RCC PLLs Configuration + Register + 0x2C + 0x20 + read-write + 0x01FF0000 + + + PLL1FRACEN + PLL1 fractional latch + enable + 0 + 1 + + + PLL1VCOSEL + PLL1 VCO selection + 1 + 1 + + + PLL1RGE + PLL1 input frequency range + 2 + 2 + + + PLL2FRACEN + PLL2 fractional latch + enable + 4 + 1 + + + PLL2VCOSEL + PLL2 VCO selection + 5 + 1 + + + PLL2RGE + PLL2 input frequency range + 6 + 2 + + + PLL3FRACEN + PLL3 fractional latch + enable + 8 + 1 + + + PLL3VCOSEL + PLL3 VCO selection + 9 + 1 + + + PLL3RGE + PLL3 input frequency range + 10 + 2 + + + DIVP1EN + PLL1 DIVP divider output + enable + 16 + 1 + + + DIVQ1EN + PLL1 DIVQ divider output + enable + 17 + 1 + + + DIVR1EN + PLL1 DIVR divider output + enable + 18 + 1 + + + DIVP2EN + PLL2 DIVP divider output + enable + 19 + 1 + + + DIVQ2EN + PLL2 DIVQ divider output + enable + 20 + 1 + + + DIVR2EN + PLL2 DIVR divider output + enable + 21 + 1 + + + DIVP3EN + PLL3 DIVP divider output + enable + 22 + 1 + + + DIVQ3EN + PLL3 DIVQ divider output + enable + 23 + 1 + + + DIVR3EN + PLL3 DIVR divider output + enable + 24 + 1 + + + + + PLL1DIVR + PLL1DIVR + RCC PLL1 Dividers Configuration + Register + 0x30 + 0x20 + read-write + 0x01010280 + + + DIVN1 + Multiplication factor for PLL1 + VCO + 0 + 9 + + + DIVP1 + PLL1 DIVP division factor + 9 + 7 + + + DIVQ1 + PLL1 DIVQ division factor + 16 + 7 + + + DIVR1 + PLL1 DIVR division factor + 24 + 7 + + + + + PLL1FRACR + PLL1FRACR + RCC PLL1 Fractional Divider + Register + 0x34 + 0x20 + read-write + 0x00000000 + + + FRACN1 + Fractional part of the multiplication + factor for PLL1 VCO + 3 + 13 + + + + + PLL2DIVR + PLL2DIVR + RCC PLL2 Dividers Configuration + Register + 0x38 + 0x20 + read-write + 0x01010280 + + + DIVN1 + Multiplication factor for PLL1 + VCO + 0 + 9 + + + DIVP1 + PLL1 DIVP division factor + 9 + 7 + + + DIVQ1 + PLL1 DIVQ division factor + 16 + 7 + + + DIVR1 + PLL1 DIVR division factor + 24 + 7 + + + + + PLL2FRACR + PLL2FRACR + RCC PLL2 Fractional Divider + Register + 0x3C + 0x20 + read-write + 0x00000000 + + + FRACN2 + Fractional part of the multiplication + factor for PLL VCO + 3 + 13 + + + + + PLL3DIVR + PLL3DIVR + RCC PLL3 Dividers Configuration + Register + 0x40 + 0x20 + read-write + 0x01010280 + + + DIVN3 + Multiplication factor for PLL1 + VCO + 0 + 9 + + + DIVP3 + PLL DIVP division factor + 9 + 7 + + + DIVQ3 + PLL DIVQ division factor + 16 + 7 + + + DIVR3 + PLL DIVR division factor + 24 + 7 + + + + + PLL3FRACR + PLL3FRACR + RCC PLL3 Fractional Divider + Register + 0x44 + 0x20 + read-write + 0x00000000 + + + FRACN3 + Fractional part of the multiplication + factor for PLL3 VCO + 3 + 13 + + + + + D1CCIPR + D1CCIPR + RCC Domain 1 Kernel Clock Configuration + Register + 0x4C + 0x20 + read-write + 0x00000000 + + + FMCSRC + FMC kernel clock source + selection + 0 + 2 + + + QSPISRC + QUADSPI kernel clock source + selection + 4 + 2 + + + SDMMCSRC + SDMMC kernel clock source + selection + 16 + 1 + + + CKPERSRC + per_ck clock source + selection + 28 + 2 + + + + + D2CCIP1R + D2CCIP1R + RCC Domain 2 Kernel Clock Configuration + Register + 0x50 + 0x20 + read-write + 0x00000000 + + + SAI1SRC + SAI1 and DFSDM1 kernel Aclk clock source + selection + 0 + 3 + + + SAI23SRC + SAI2 and SAI3 kernel clock source + selection + 6 + 3 + + + SPI123SRC + SPI/I2S1,2 and 3 kernel clock source + selection + 12 + 3 + + + SPI45SRC + SPI4 and 5 kernel clock source + selection + 16 + 3 + + + SPDIFSRC + SPDIFRX kernel clock source + selection + 20 + 2 + + + DFSDM1SRC + DFSDM1 kernel Clk clock source + selection + 24 + 1 + + + FDCANSRC + FDCAN kernel clock source + selection + 28 + 2 + + + SWPSRC + SWPMI kernel clock source + selection + 31 + 1 + + + + + D2CCIP2R + D2CCIP2R + RCC Domain 2 Kernel Clock Configuration + Register + 0x54 + 0x20 + read-write + 0x00000000 + + + USART234578SRC + USART2/3, UART4,5, 7/8 (APB1) kernel + clock source selection + 0 + 3 + + + USART16SRC + USART1 and 6 kernel clock source + selection + 3 + 3 + + + RNGSRC + RNG kernel clock source + selection + 8 + 2 + + + I2C123SRC + I2C1,2,3 kernel clock source + selection + 12 + 2 + + + USBSRC + USBOTG 1 and 2 kernel clock source + selection + 20 + 2 + + + CECSRC + HDMI-CEC kernel clock source + selection + 22 + 2 + + + LPTIM1SRC + LPTIM1 kernel clock source + selection + 28 + 3 + + + + + D3CCIPR + D3CCIPR + RCC Domain 3 Kernel Clock Configuration + Register + 0x58 + 0x20 + read-write + 0x00000000 + + + LPUART1SRC + LPUART1 kernel clock source + selection + 0 + 3 + + + I2C4SRC + I2C4 kernel clock source + selection + 8 + 2 + + + LPTIM2SRC + LPTIM2 kernel clock source + selection + 10 + 3 + + + LPTIM345SRC + LPTIM3,4,5 kernel clock source + selection + 13 + 3 + + + ADCSRC + SAR ADC kernel clock source + selection + 16 + 2 + + + SAI4ASRC + Sub-Block A of SAI4 kernel clock source + selection + 21 + 3 + + + SAI4BSRC + Sub-Block B of SAI4 kernel clock source + selection + 24 + 3 + + + SPI6SRC + SPI6 kernel clock source + selection + 28 + 3 + + + + + CIER + CIER + RCC Clock Source Interrupt Enable + Register + 0x60 + 0x20 + read-write + 0x00000000 + + + LSIRDYIE + LSI ready Interrupt Enable + 0 + 1 + + + LSERDYIE + LSE ready Interrupt Enable + 1 + 1 + + + HSIRDYIE + HSI ready Interrupt Enable + 2 + 1 + + + HSERDYIE + HSE ready Interrupt Enable + 3 + 1 + + + CSIRDYIE + CSI ready Interrupt Enable + 4 + 1 + + + RC48RDYIE + RC48 ready Interrupt + Enable + 5 + 1 + + + PLL1RDYIE + PLL1 ready Interrupt + Enable + 6 + 1 + + + PLL2RDYIE + PLL2 ready Interrupt + Enable + 7 + 1 + + + PLL3RDYIE + PLL3 ready Interrupt + Enable + 8 + 1 + + + LSECSSIE + LSE clock security system Interrupt + Enable + 9 + 1 + + + + + CIFR + CIFR + RCC Clock Source Interrupt Flag + Register + 0x64 + 0x20 + read-write + 0x00000000 + + + LSIRDYF + LSI ready Interrupt Flag + 0 + 1 + + + LSERDYF + LSE ready Interrupt Flag + 1 + 1 + + + HSIRDYF + HSI ready Interrupt Flag + 2 + 1 + + + HSERDYF + HSE ready Interrupt Flag + 3 + 1 + + + CSIRDY + CSI ready Interrupt Flag + 4 + 1 + + + RC48RDYF + RC48 ready Interrupt Flag + 5 + 1 + + + PLL1RDYF + PLL1 ready Interrupt Flag + 6 + 1 + + + PLL2RDYF + PLL2 ready Interrupt Flag + 7 + 1 + + + PLL3RDYF + PLL3 ready Interrupt Flag + 8 + 1 + + + LSECSSF + LSE clock security system Interrupt + Flag + 9 + 1 + + + HSECSSF + HSE clock security system Interrupt + Flag + 10 + 1 + + + + + CICR + CICR + RCC Clock Source Interrupt Clear + Register + 0x68 + 0x20 + read-write + 0x00000000 + + + LSIRDYC + LSI ready Interrupt Clear + 0 + 1 + + + LSERDYC + LSE ready Interrupt Clear + 1 + 1 + + + HSIRDYC + HSI ready Interrupt Clear + 2 + 1 + + + HSERDYC + HSE ready Interrupt Clear + 3 + 1 + + + HSE_ready_Interrupt_Clear + CSI ready Interrupt Clear + 4 + 1 + + + RC48RDYC + RC48 ready Interrupt Clear + 5 + 1 + + + PLL1RDYC + PLL1 ready Interrupt Clear + 6 + 1 + + + PLL2RDYC + PLL2 ready Interrupt Clear + 7 + 1 + + + PLL3RDYC + PLL3 ready Interrupt Clear + 8 + 1 + + + LSECSSC + LSE clock security system Interrupt + Clear + 9 + 1 + + + HSECSSC + HSE clock security system Interrupt + Clear + 10 + 1 + + + + + BDCR + BDCR + RCC Backup Domain Control + Register + 0x70 + 0x20 + read-write + 0x00000000 + + + LSEON + LSE oscillator enabled + 0 + 1 + + + LSERDY + LSE oscillator ready + 1 + 1 + + + LSEBYP + LSE oscillator bypass + 2 + 1 + + + LSEDRV + LSE oscillator driving + capability + 3 + 2 + + + LSECSSON + LSE clock security system + enable + 5 + 1 + + + LSECSSD + LSE clock security system failure + detection + 6 + 1 + + + RTCSRC + RTC clock source selection + 8 + 2 + + + RTCEN + RTC clock enable + 15 + 1 + + + VSWRST + VSwitch domain software + reset + 16 + 1 + + + + + CSR + CSR + RCC Clock Control and Status + Register + 0x74 + 0x20 + read-write + 0x00000000 + + + LSION + LSI oscillator enable + 0 + 1 + + + LSIRDY + LSI oscillator ready + 1 + 1 + + + + + AHB3RSTR + AHB3RSTR + RCC AHB3 Reset Register + 0x7C + 0x20 + read-write + 0x00000000 + + + MDMARST + MDMA block reset + 0 + 1 + + + DMA2DRST + DMA2D block reset + 4 + 1 + + + JPGDECRST + JPGDEC block reset + 5 + 1 + + + FMCRST + FMC block reset + 12 + 1 + + + QSPIRST + QUADSPI and QUADSPI delay block + reset + 14 + 1 + + + SDMMC1RST + SDMMC1 and SDMMC1 delay block + reset + 16 + 1 + + + CPURST + CPU reset + 31 + 1 + + + + + AHB1RSTR + AHB1RSTR + RCC AHB1 Peripheral Reset + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + DMA1RST + DMA1 block reset + 0 + 1 + + + DMA2RST + DMA2 block reset + 1 + 1 + + + ADC12RST + ADC1&2 block reset + 5 + 1 + + + ETH1MACRST + ETH1MAC block reset + 15 + 1 + + + USB1OTGRST + USB1OTG block reset + 25 + 1 + + + USB2OTGRST + USB2OTG block reset + 27 + 1 + + + + + AHB2RSTR + AHB2RSTR + RCC AHB2 Peripheral Reset + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CAMITFRST + CAMITF block reset + 0 + 1 + + + CRYPTRST + Cryptography block reset + 4 + 1 + + + HASHRST + Hash block reset + 5 + 1 + + + RNGRST + Random Number Generator block + reset + 6 + 1 + + + SDMMC2RST + SDMMC2 and SDMMC2 Delay block + reset + 9 + 1 + + + + + AHB4RSTR + AHB4RSTR + RCC AHB4 Peripheral Reset + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + GPIOARST + GPIO block reset + 0 + 1 + + + GPIOBRST + GPIO block reset + 1 + 1 + + + GPIOCRST + GPIO block reset + 2 + 1 + + + GPIODRST + GPIO block reset + 3 + 1 + + + GPIOERST + GPIO block reset + 4 + 1 + + + GPIOFRST + GPIO block reset + 5 + 1 + + + GPIOGRST + GPIO block reset + 6 + 1 + + + GPIOHRST + GPIO block reset + 7 + 1 + + + GPIOIRST + GPIO block reset + 8 + 1 + + + GPIOJRST + GPIO block reset + 9 + 1 + + + GPIOKRST + GPIO block reset + 10 + 1 + + + CRCRST + CRC block reset + 19 + 1 + + + BDMARST + BDMA block reset + 21 + 1 + + + ADC3RST + ADC3 block reset + 24 + 1 + + + HSEMRST + HSEM block reset + 25 + 1 + + + + + APB3RSTR + APB3RSTR + RCC APB3 Peripheral Reset + Register + 0x8C + 0x20 + read-write + 0x00000000 + + + LTDCRST + LTDC block reset + 3 + 1 + + + + + APB1LRSTR + APB1LRSTR + RCC APB1 Peripheral Reset + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + TIM2RST + TIM block reset + 0 + 1 + + + TIM3RST + TIM block reset + 1 + 1 + + + TIM4RST + TIM block reset + 2 + 1 + + + TIM5RST + TIM block reset + 3 + 1 + + + TIM6RST + TIM block reset + 4 + 1 + + + TIM7RST + TIM block reset + 5 + 1 + + + TIM12RST + TIM block reset + 6 + 1 + + + TIM13RST + TIM block reset + 7 + 1 + + + TIM14RST + TIM block reset + 8 + 1 + + + LPTIM1RST + TIM block reset + 9 + 1 + + + SPI2RST + SPI2 block reset + 14 + 1 + + + SPI3RST + SPI3 block reset + 15 + 1 + + + SPDIFRXRST + SPDIFRX block reset + 16 + 1 + + + USART2RST + USART2 block reset + 17 + 1 + + + USART3RST + USART3 block reset + 18 + 1 + + + UART4RST + UART4 block reset + 19 + 1 + + + UART5RST + UART5 block reset + 20 + 1 + + + I2C1RST + I2C1 block reset + 21 + 1 + + + I2C2RST + I2C2 block reset + 22 + 1 + + + I2C3RST + I2C3 block reset + 23 + 1 + + + CECRST + HDMI-CEC block reset + 27 + 1 + + + DAC12RST + DAC1 and 2 Blocks Reset + 29 + 1 + + + USART7RST + USART7 block reset + 30 + 1 + + + USART8RST + USART8 block reset + 31 + 1 + + + + + APB1HRSTR + APB1HRSTR + RCC APB1 Peripheral Reset + Register + 0x94 + 0x20 + read-write + 0x00000000 + + + CRSRST + Clock Recovery System + reset + 1 + 1 + + + SWPRST + SWPMI block reset + 2 + 1 + + + OPAMPRST + OPAMP block reset + 4 + 1 + + + MDIOSRST + MDIOS block reset + 5 + 1 + + + FDCANRST + FDCAN block reset + 8 + 1 + + + + + APB2RSTR + APB2RSTR + RCC APB2 Peripheral Reset + Register + 0x98 + 0x20 + read-write + 0x00000000 + + + TIM1RST + TIM1 block reset + 0 + 1 + + + TIM8RST + TIM8 block reset + 1 + 1 + + + USART1RST + USART1 block reset + 4 + 1 + + + USART6RST + USART6 block reset + 5 + 1 + + + SPI1RST + SPI1 block reset + 12 + 1 + + + SPI4RST + SPI4 block reset + 13 + 1 + + + TIM15RST + TIM15 block reset + 16 + 1 + + + TIM16RST + TIM16 block reset + 17 + 1 + + + TIM17RST + TIM17 block reset + 18 + 1 + + + SPI5RST + SPI5 block reset + 20 + 1 + + + SAI1RST + SAI1 block reset + 22 + 1 + + + SAI2RST + SAI2 block reset + 23 + 1 + + + SAI3RST + SAI3 block reset + 24 + 1 + + + DFSDM1RST + DFSDM1 block reset + 28 + 1 + + + HRTIMRST + HRTIM block reset + 29 + 1 + + + + + APB4RSTR + APB4RSTR + RCC APB4 Peripheral Reset + Register + 0x9C + 0x20 + read-write + 0x00000000 + + + SYSCFGRST + SYSCFG block reset + 1 + 1 + + + LPUART1RST + LPUART1 block reset + 3 + 1 + + + SPI6RST + SPI6 block reset + 5 + 1 + + + I2C4RST + I2C4 block reset + 7 + 1 + + + LPTIM2RST + LPTIM2 block reset + 9 + 1 + + + LPTIM3RST + LPTIM3 block reset + 10 + 1 + + + LPTIM4RST + LPTIM4 block reset + 11 + 1 + + + LPTIM5RST + LPTIM5 block reset + 12 + 1 + + + COMP12RST + COMP12 Blocks Reset + 14 + 1 + + + VREFRST + VREF block reset + 15 + 1 + + + SAI4RST + SAI4 block reset + 21 + 1 + + + + + GCR + GCR + RCC Global Control Register + 0xA0 + 0x20 + read-write + 0x00000000 + + + WW1RSC + WWDG1 reset scope control + 0 + 1 + + + + + D3AMR + D3AMR + RCC D3 Autonomous mode + Register + 0xA8 + 0x20 + read-write + 0x00000000 + + + BDMAAMEN + BDMA and DMAMUX Autonomous mode + enable + 0 + 1 + + + LPUART1AMEN + LPUART1 Autonomous mode + enable + 3 + 1 + + + SPI6AMEN + SPI6 Autonomous mode + enable + 5 + 1 + + + I2C4AMEN + I2C4 Autonomous mode + enable + 7 + 1 + + + LPTIM2AMEN + LPTIM2 Autonomous mode + enable + 9 + 1 + + + LPTIM3AMEN + LPTIM3 Autonomous mode + enable + 10 + 1 + + + LPTIM4AMEN + LPTIM4 Autonomous mode + enable + 11 + 1 + + + LPTIM5AMEN + LPTIM5 Autonomous mode + enable + 12 + 1 + + + COMP12AMEN + COMP12 Autonomous mode + enable + 14 + 1 + + + VREFAMEN + VREF Autonomous mode + enable + 15 + 1 + + + RTCAMEN + RTC Autonomous mode enable + 16 + 1 + + + CRCAMEN + CRC Autonomous mode enable + 19 + 1 + + + SAI4AMEN + SAI4 Autonomous mode + enable + 21 + 1 + + + ADC3AMEN + ADC3 Autonomous mode + enable + 24 + 1 + + + BKPRAMAMEN + Backup RAM Autonomous mode + enable + 28 + 1 + + + SRAM4AMEN + SRAM4 Autonomous mode + enable + 29 + 1 + + + + + RSR + RSR + RCC Reset Status Register + 0xD0 + 0x20 + read-write + 0x00000000 + + + RMVF + Remove reset flag + 16 + 1 + + + CPURSTF + CPU reset flag + 17 + 1 + + + D1RSTF + D1 domain power switch reset + flag + 19 + 1 + + + D2RSTF + D2 domain power switch reset + flag + 20 + 1 + + + BORRSTF + BOR reset flag + 21 + 1 + + + PINRSTF + Pin reset flag (NRST) + 22 + 1 + + + PORRSTF + POR/PDR reset flag + 23 + 1 + + + SFTRSTF + System reset from CPU reset + flag + 24 + 1 + + + IWDG1RSTF + Independent Watchdog reset + flag + 26 + 1 + + + WWDG1RSTF + Window Watchdog reset flag + 28 + 1 + + + LPWRRSTF + Reset due to illegal D1 DStandby or CPU + CStop flag + 30 + 1 + + + + + C1_RSR + C1_RSR + RCC Reset Status Register + 0x130 + 0x20 + read-write + 0x00000000 + + + RMVF + Remove reset flag + 16 + 1 + + + CPURSTF + CPU reset flag + 17 + 1 + + + D1RSTF + D1 domain power switch reset + flag + 19 + 1 + + + D2RSTF + D2 domain power switch reset + flag + 20 + 1 + + + BORRSTF + BOR reset flag + 21 + 1 + + + PINRSTF + Pin reset flag (NRST) + 22 + 1 + + + PORRSTF + POR/PDR reset flag + 23 + 1 + + + SFTRSTF + System reset from CPU reset + flag + 24 + 1 + + + IWDG1RSTF + Independent Watchdog reset + flag + 26 + 1 + + + WWDG1RSTF + Window Watchdog reset flag + 28 + 1 + + + LPWRRSTF + Reset due to illegal D1 DStandby or CPU + CStop flag + 30 + 1 + + + + + C1_AHB3ENR + C1_AHB3ENR + RCC AHB3 Clock Register + 0x134 + 0x20 + read-write + 0x00000000 + + + MDMAEN + MDMA Peripheral Clock + Enable + 0 + 1 + + + DMA2DEN + DMA2D Peripheral Clock + Enable + 4 + 1 + + + JPGDECEN + JPGDEC Peripheral Clock + Enable + 5 + 1 + + + FMCEN + FMC Peripheral Clocks + Enable + 12 + 1 + + + QSPIEN + QUADSPI and QUADSPI Delay Clock + Enable + 14 + 1 + + + SDMMC1EN + SDMMC1 and SDMMC1 Delay Clock + Enable + 16 + 1 + + + + + AHB3ENR + AHB3ENR + RCC AHB3 Clock Register + 0xD4 + 0x20 + read-write + 0x00000000 + + + MDMAEN + MDMA Peripheral Clock + Enable + 0 + 1 + + + DMA2DEN + DMA2D Peripheral Clock + Enable + 4 + 1 + + + JPGDECEN + JPGDEC Peripheral Clock + Enable + 5 + 1 + + + FMCEN + FMC Peripheral Clocks + Enable + 12 + 1 + + + QSPIEN + QUADSPI and QUADSPI Delay Clock + Enable + 14 + 1 + + + SDMMC1EN + SDMMC1 and SDMMC1 Delay Clock + Enable + 16 + 1 + + + + + AHB1ENR + AHB1ENR + RCC AHB1 Clock Register + 0xD8 + 0x20 + read-write + 0x00000000 + + + DMA1EN + DMA1 Clock Enable + 0 + 1 + + + DMA2EN + DMA2 Clock Enable + 1 + 1 + + + ADC12EN + ADC1/2 Peripheral Clocks + Enable + 5 + 1 + + + ETH1MACEN + Ethernet MAC bus interface Clock + Enable + 15 + 1 + + + ETH1TXEN + Ethernet Transmission Clock + Enable + 16 + 1 + + + ETH1RXEN + Ethernet Reception Clock + Enable + 17 + 1 + + + USB2OTGHSULPIEN + Enable USB_PHY2 clocks + 18 + 1 + + + USB1OTGEN + USB1OTG Peripheral Clocks + Enable + 25 + 1 + + + USB1ULPIEN + USB_PHY1 Clocks Enable + 26 + 1 + + + USB2OTGEN + USB2OTG Peripheral Clocks + Enable + 27 + 1 + + + USB2ULPIEN + USB_PHY2 Clocks Enable + 28 + 1 + + + + + C1_AHB1ENR + C1_AHB1ENR + RCC AHB1 Clock Register + 0x138 + 0x20 + read-write + 0x00000000 + + + DMA1EN + DMA1 Clock Enable + 0 + 1 + + + DMA2EN + DMA2 Clock Enable + 1 + 1 + + + ADC12EN + ADC1/2 Peripheral Clocks + Enable + 5 + 1 + + + ETH1MACEN + Ethernet MAC bus interface Clock + Enable + 15 + 1 + + + ETH1TXEN + Ethernet Transmission Clock + Enable + 16 + 1 + + + ETH1RXEN + Ethernet Reception Clock + Enable + 17 + 1 + + + USB1OTGEN + USB1OTG Peripheral Clocks + Enable + 25 + 1 + + + USB1ULPIEN + USB_PHY1 Clocks Enable + 26 + 1 + + + USB2OTGEN + USB2OTG Peripheral Clocks + Enable + 27 + 1 + + + USB2ULPIEN + USB_PHY2 Clocks Enable + 28 + 1 + + + + + C1_AHB2ENR + C1_AHB2ENR + RCC AHB2 Clock Register + 0x13C + 0x20 + read-write + 0x00000000 + + + CAMITFEN + CAMITF peripheral clock + enable + 0 + 1 + + + CRYPTEN + CRYPT peripheral clock + enable + 4 + 1 + + + HASHEN + HASH peripheral clock + enable + 5 + 1 + + + RNGEN + RNG peripheral clocks + enable + 6 + 1 + + + SDMMC2EN + SDMMC2 and SDMMC2 delay clock + enable + 9 + 1 + + + SRAM1EN + SRAM1 block enable + 29 + 1 + + + SRAM2EN + SRAM2 block enable + 30 + 1 + + + SRAM3EN + SRAM3 block enable + 31 + 1 + + + + + AHB2ENR + AHB2ENR + RCC AHB2 Clock Register + 0xDC + 0x20 + read-write + 0x00000000 + + + CAMITFEN + CAMITF peripheral clock + enable + 0 + 1 + + + CRYPTEN + CRYPT peripheral clock + enable + 4 + 1 + + + HASHEN + HASH peripheral clock + enable + 5 + 1 + + + RNGEN + RNG peripheral clocks + enable + 6 + 1 + + + SDMMC2EN + SDMMC2 and SDMMC2 delay clock + enable + 9 + 1 + + + SRAM1EN + SRAM1 block enable + 29 + 1 + + + SRAM2EN + SRAM2 block enable + 30 + 1 + + + SRAM3EN + SRAM3 block enable + 31 + 1 + + + + + AHB4ENR + AHB4ENR + RCC AHB4 Clock Register + 0xE0 + 0x20 + read-write + 0x00000000 + + + GPIOAEN + 0GPIO peripheral clock + enable + 0 + 1 + + + GPIOBEN + 0GPIO peripheral clock + enable + 1 + 1 + + + GPIOCEN + 0GPIO peripheral clock + enable + 2 + 1 + + + GPIODEN + 0GPIO peripheral clock + enable + 3 + 1 + + + GPIOEEN + 0GPIO peripheral clock + enable + 4 + 1 + + + GPIOFEN + 0GPIO peripheral clock + enable + 5 + 1 + + + GPIOGEN + 0GPIO peripheral clock + enable + 6 + 1 + + + GPIOHEN + 0GPIO peripheral clock + enable + 7 + 1 + + + GPIOIEN + 0GPIO peripheral clock + enable + 8 + 1 + + + GPIOJEN + 0GPIO peripheral clock + enable + 9 + 1 + + + GPIOKEN + 0GPIO peripheral clock + enable + 10 + 1 + + + CRCEN + CRC peripheral clock + enable + 19 + 1 + + + BDMAEN + BDMA and DMAMUX2 Clock + Enable + 21 + 1 + + + ADC3EN + ADC3 Peripheral Clocks + Enable + 24 + 1 + + + HSEMEN + HSEM peripheral clock + enable + 25 + 1 + + + BKPRAMEN + Backup RAM Clock Enable + 28 + 1 + + + + + C1_AHB4ENR + C1_AHB4ENR + RCC AHB4 Clock Register + 0x140 + 0x20 + read-write + 0x00000000 + + + GPIOAEN + 0GPIO peripheral clock + enable + 0 + 1 + + + GPIOBEN + 0GPIO peripheral clock + enable + 1 + 1 + + + GPIOCEN + 0GPIO peripheral clock + enable + 2 + 1 + + + GPIODEN + 0GPIO peripheral clock + enable + 3 + 1 + + + GPIOEEN + 0GPIO peripheral clock + enable + 4 + 1 + + + GPIOFEN + 0GPIO peripheral clock + enable + 5 + 1 + + + GPIOGEN + 0GPIO peripheral clock + enable + 6 + 1 + + + GPIOHEN + 0GPIO peripheral clock + enable + 7 + 1 + + + GPIOIEN + 0GPIO peripheral clock + enable + 8 + 1 + + + GPIOJEN + 0GPIO peripheral clock + enable + 9 + 1 + + + GPIOKEN + 0GPIO peripheral clock + enable + 10 + 1 + + + CRCEN + CRC peripheral clock + enable + 19 + 1 + + + BDMAEN + BDMA and DMAMUX2 Clock + Enable + 21 + 1 + + + ADC3EN + ADC3 Peripheral Clocks + Enable + 24 + 1 + + + HSEMEN + HSEM peripheral clock + enable + 25 + 1 + + + BKPRAMEN + Backup RAM Clock Enable + 28 + 1 + + + + + C1_APB3ENR + C1_APB3ENR + RCC APB3 Clock Register + 0x144 + 0x20 + read-write + 0x00000000 + + + LTDCEN + LTDC peripheral clock + enable + 3 + 1 + + + WWDG1EN + WWDG1 Clock Enable + 6 + 1 + + + + + APB3ENR + APB3ENR + RCC APB3 Clock Register + 0xE4 + 0x20 + read-write + 0x00000000 + + + LTDCEN + LTDC peripheral clock + enable + 3 + 1 + + + WWDG1EN + WWDG1 Clock Enable + 6 + 1 + + + + + APB1LENR + APB1LENR + RCC APB1 Clock Register + 0xE8 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM peripheral clock + enable + 0 + 1 + + + TIM3EN + TIM peripheral clock + enable + 1 + 1 + + + TIM4EN + TIM peripheral clock + enable + 2 + 1 + + + TIM5EN + TIM peripheral clock + enable + 3 + 1 + + + TIM6EN + TIM peripheral clock + enable + 4 + 1 + + + TIM7EN + TIM peripheral clock + enable + 5 + 1 + + + TIM12EN + TIM peripheral clock + enable + 6 + 1 + + + TIM13EN + TIM peripheral clock + enable + 7 + 1 + + + TIM14EN + TIM peripheral clock + enable + 8 + 1 + + + LPTIM1EN + LPTIM1 Peripheral Clocks + Enable + 9 + 1 + + + SPI2EN + SPI2 Peripheral Clocks + Enable + 14 + 1 + + + SPI3EN + SPI3 Peripheral Clocks + Enable + 15 + 1 + + + SPDIFRXEN + SPDIFRX Peripheral Clocks + Enable + 16 + 1 + + + USART2EN + USART2 Peripheral Clocks + Enable + 17 + 1 + + + USART3EN + USART3 Peripheral Clocks + Enable + 18 + 1 + + + UART4EN + UART4 Peripheral Clocks + Enable + 19 + 1 + + + UART5EN + UART5 Peripheral Clocks + Enable + 20 + 1 + + + I2C1EN + I2C1 Peripheral Clocks + Enable + 21 + 1 + + + I2C2EN + I2C2 Peripheral Clocks + Enable + 22 + 1 + + + I2C3EN + I2C3 Peripheral Clocks + Enable + 23 + 1 + + + CECEN + HDMI-CEC peripheral clock + enable + 27 + 1 + + + DAC12EN + DAC1&2 peripheral clock + enable + 29 + 1 + + + USART7EN + USART7 Peripheral Clocks + Enable + 30 + 1 + + + USART8EN + USART8 Peripheral Clocks + Enable + 31 + 1 + + + + + C1_APB1LENR + C1_APB1LENR + RCC APB1 Clock Register + 0x148 + 0x20 + read-write + 0x00000000 + + + TIM2EN + TIM peripheral clock + enable + 0 + 1 + + + TIM3EN + TIM peripheral clock + enable + 1 + 1 + + + TIM4EN + TIM peripheral clock + enable + 2 + 1 + + + TIM5EN + TIM peripheral clock + enable + 3 + 1 + + + TIM6EN + TIM peripheral clock + enable + 4 + 1 + + + TIM7EN + TIM peripheral clock + enable + 5 + 1 + + + TIM12EN + TIM peripheral clock + enable + 6 + 1 + + + TIM13EN + TIM peripheral clock + enable + 7 + 1 + + + TIM14EN + TIM peripheral clock + enable + 8 + 1 + + + LPTIM1EN + LPTIM1 Peripheral Clocks + Enable + 9 + 1 + + + SPI2EN + SPI2 Peripheral Clocks + Enable + 14 + 1 + + + SPI3EN + SPI3 Peripheral Clocks + Enable + 15 + 1 + + + SPDIFRXEN + SPDIFRX Peripheral Clocks + Enable + 16 + 1 + + + USART2EN + USART2 Peripheral Clocks + Enable + 17 + 1 + + + USART3EN + USART3 Peripheral Clocks + Enable + 18 + 1 + + + UART4EN + UART4 Peripheral Clocks + Enable + 19 + 1 + + + UART5EN + UART5 Peripheral Clocks + Enable + 20 + 1 + + + I2C1EN + I2C1 Peripheral Clocks + Enable + 21 + 1 + + + I2C2EN + I2C2 Peripheral Clocks + Enable + 22 + 1 + + + I2C3EN + I2C3 Peripheral Clocks + Enable + 23 + 1 + + + HDMICECEN + HDMI-CEC peripheral clock + enable + 27 + 1 + + + DAC12EN + DAC1&2 peripheral clock + enable + 29 + 1 + + + USART7EN + USART7 Peripheral Clocks + Enable + 30 + 1 + + + USART8EN + USART8 Peripheral Clocks + Enable + 31 + 1 + + + + + APB1HENR + APB1HENR + RCC APB1 Clock Register + 0xEC + 0x20 + read-write + 0x00000000 + + + CRSEN + Clock Recovery System peripheral clock + enable + 1 + 1 + + + SWPEN + SWPMI Peripheral Clocks + Enable + 2 + 1 + + + OPAMPEN + OPAMP peripheral clock + enable + 4 + 1 + + + MDIOSEN + MDIOS peripheral clock + enable + 5 + 1 + + + FDCANEN + FDCAN Peripheral Clocks + Enable + 8 + 1 + + + + + C1_APB1HENR + C1_APB1HENR + RCC APB1 Clock Register + 0x14C + 0x20 + read-write + 0x00000000 + + + CRSEN + Clock Recovery System peripheral clock + enable + 1 + 1 + + + SWPEN + SWPMI Peripheral Clocks + Enable + 2 + 1 + + + OPAMPEN + OPAMP peripheral clock + enable + 4 + 1 + + + MDIOSEN + MDIOS peripheral clock + enable + 5 + 1 + + + FDCANEN + FDCAN Peripheral Clocks + Enable + 8 + 1 + + + + + C1_APB2ENR + C1_APB2ENR + RCC APB2 Clock Register + 0x150 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 peripheral clock + enable + 0 + 1 + + + TIM8EN + TIM8 peripheral clock + enable + 1 + 1 + + + USART1EN + USART1 Peripheral Clocks + Enable + 4 + 1 + + + USART6EN + USART6 Peripheral Clocks + Enable + 5 + 1 + + + SPI1EN + SPI1 Peripheral Clocks + Enable + 12 + 1 + + + SPI4EN + SPI4 Peripheral Clocks + Enable + 13 + 1 + + + TIM16EN + TIM16 peripheral clock + enable + 17 + 1 + + + TIM15EN + TIM15 peripheral clock + enable + 16 + 1 + + + TIM17EN + TIM17 peripheral clock + enable + 18 + 1 + + + SPI5EN + SPI5 Peripheral Clocks + Enable + 20 + 1 + + + SAI1EN + SAI1 Peripheral Clocks + Enable + 22 + 1 + + + SAI2EN + SAI2 Peripheral Clocks + Enable + 23 + 1 + + + SAI3EN + SAI3 Peripheral Clocks + Enable + 24 + 1 + + + DFSDM1EN + DFSDM1 Peripheral Clocks + Enable + 28 + 1 + + + HRTIMEN + HRTIM peripheral clock + enable + 29 + 1 + + + + + APB2ENR + APB2ENR + RCC APB2 Clock Register + 0xF0 + 0x20 + read-write + 0x00000000 + + + TIM1EN + TIM1 peripheral clock + enable + 0 + 1 + + + TIM8EN + TIM8 peripheral clock + enable + 1 + 1 + + + USART1EN + USART1 Peripheral Clocks + Enable + 4 + 1 + + + USART6EN + USART6 Peripheral Clocks + Enable + 5 + 1 + + + SPI1EN + SPI1 Peripheral Clocks + Enable + 12 + 1 + + + SPI4EN + SPI4 Peripheral Clocks + Enable + 13 + 1 + + + TIM16EN + TIM16 peripheral clock + enable + 17 + 1 + + + TIM15EN + TIM15 peripheral clock + enable + 16 + 1 + + + TIM17EN + TIM17 peripheral clock + enable + 18 + 1 + + + SPI5EN + SPI5 Peripheral Clocks + Enable + 20 + 1 + + + SAI1EN + SAI1 Peripheral Clocks + Enable + 22 + 1 + + + SAI2EN + SAI2 Peripheral Clocks + Enable + 23 + 1 + + + SAI3EN + SAI3 Peripheral Clocks + Enable + 24 + 1 + + + DFSDM1EN + DFSDM1 Peripheral Clocks + Enable + 28 + 1 + + + HRTIMEN + HRTIM peripheral clock + enable + 29 + 1 + + + + + APB4ENR + APB4ENR + RCC APB4 Clock Register + 0xF4 + 0x20 + read-write + 0x00000000 + + + SYSCFGEN + SYSCFG peripheral clock + enable + 1 + 1 + + + LPUART1EN + LPUART1 Peripheral Clocks + Enable + 3 + 1 + + + SPI6EN + SPI6 Peripheral Clocks + Enable + 5 + 1 + + + I2C4EN + I2C4 Peripheral Clocks + Enable + 7 + 1 + + + LPTIM2EN + LPTIM2 Peripheral Clocks + Enable + 9 + 1 + + + LPTIM3EN + LPTIM3 Peripheral Clocks + Enable + 10 + 1 + + + LPTIM4EN + LPTIM4 Peripheral Clocks + Enable + 11 + 1 + + + LPTIM5EN + LPTIM5 Peripheral Clocks + Enable + 12 + 1 + + + COMP12EN + COMP1/2 peripheral clock + enable + 14 + 1 + + + VREFEN + VREF peripheral clock + enable + 15 + 1 + + + RTCAPBEN + RTC APB Clock Enable + 16 + 1 + + + SAI4EN + SAI4 Peripheral Clocks + Enable + 21 + 1 + + + + + C1_APB4ENR + C1_APB4ENR + RCC APB4 Clock Register + 0x154 + 0x20 + read-write + 0x00000000 + + + SYSCFGEN + SYSCFG peripheral clock + enable + 1 + 1 + + + LPUART1EN + LPUART1 Peripheral Clocks + Enable + 3 + 1 + + + SPI6EN + SPI6 Peripheral Clocks + Enable + 5 + 1 + + + I2C4EN + I2C4 Peripheral Clocks + Enable + 7 + 1 + + + LPTIM2EN + LPTIM2 Peripheral Clocks + Enable + 9 + 1 + + + LPTIM3EN + LPTIM3 Peripheral Clocks + Enable + 10 + 1 + + + LPTIM4EN + LPTIM4 Peripheral Clocks + Enable + 11 + 1 + + + LPTIM5EN + LPTIM5 Peripheral Clocks + Enable + 12 + 1 + + + COMP12EN + COMP1/2 peripheral clock + enable + 14 + 1 + + + VREFEN + VREF peripheral clock + enable + 15 + 1 + + + RTCAPBEN + RTC APB Clock Enable + 16 + 1 + + + SAI4EN + SAI4 Peripheral Clocks + Enable + 21 + 1 + + + + + C1_AHB3LPENR + C1_AHB3LPENR + RCC AHB3 Sleep Clock Register + 0x15C + 0x20 + read-write + 0x00000000 + + + MDMALPEN + MDMA Clock Enable During CSleep + Mode + 0 + 1 + + + DMA2DLPEN + DMA2D Clock Enable During CSleep + Mode + 4 + 1 + + + JPGDECLPEN + JPGDEC Clock Enable During CSleep + Mode + 5 + 1 + + + FLITFLPEN + FLITF Clock Enable During CSleep + Mode + 8 + 1 + + + FMCLPEN + FMC Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + QSPILPEN + QUADSPI and QUADSPI Delay Clock Enable + During CSleep Mode + 14 + 1 + + + SDMMC1LPEN + SDMMC1 and SDMMC1 Delay Clock Enable + During CSleep Mode + 16 + 1 + + + D1DTCM1LPEN + D1DTCM1 Block Clock Enable During CSleep + mode + 28 + 1 + + + DTCM2LPEN + D1 DTCM2 Block Clock Enable During + CSleep mode + 29 + 1 + + + ITCMLPEN + D1ITCM Block Clock Enable During CSleep + mode + 30 + 1 + + + AXISRAMLPEN + AXISRAM Block Clock Enable During CSleep + mode + 31 + 1 + + + + + AHB3LPENR + AHB3LPENR + RCC AHB3 Sleep Clock Register + 0xFC + 0x20 + read-write + 0x00000000 + + + MDMALPEN + MDMA Clock Enable During CSleep + Mode + 0 + 1 + + + DMA2DLPEN + DMA2D Clock Enable During CSleep + Mode + 4 + 1 + + + JPGDECLPEN + JPGDEC Clock Enable During CSleep + Mode + 5 + 1 + + + FLASHLPEN + FLITF Clock Enable During CSleep + Mode + 8 + 1 + + + FMCLPEN + FMC Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + QSPILPEN + QUADSPI and QUADSPI Delay Clock Enable + During CSleep Mode + 14 + 1 + + + SDMMC1LPEN + SDMMC1 and SDMMC1 Delay Clock Enable + During CSleep Mode + 16 + 1 + + + D1DTCM1LPEN + D1DTCM1 Block Clock Enable During CSleep + mode + 28 + 1 + + + DTCM2LPEN + D1 DTCM2 Block Clock Enable During + CSleep mode + 29 + 1 + + + ITCMLPEN + D1ITCM Block Clock Enable During CSleep + mode + 30 + 1 + + + AXISRAMLPEN + AXISRAM Block Clock Enable During CSleep + mode + 31 + 1 + + + + + AHB1LPENR + AHB1LPENR + RCC AHB1 Sleep Clock Register + 0x100 + 0x20 + read-write + 0x00000000 + + + DMA1LPEN + DMA1 Clock Enable During CSleep + Mode + 0 + 1 + + + DMA2LPEN + DMA2 Clock Enable During CSleep + Mode + 1 + 1 + + + ADC12LPEN + ADC1/2 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + ETH1MACLPEN + Ethernet MAC bus interface Clock Enable + During CSleep Mode + 15 + 1 + + + ETH1TXLPEN + Ethernet Transmission Clock Enable + During CSleep Mode + 16 + 1 + + + ETH1RXLPEN + Ethernet Reception Clock Enable During + CSleep Mode + 17 + 1 + + + USB1OTGHSLPEN + USB1OTG peripheral clock enable during + CSleep mode + 25 + 1 + + + USB1OTGHSULPILPEN + USB_PHY1 clock enable during CSleep + mode + 26 + 1 + + + USB2OTGHSLPEN + USB2OTG peripheral clock enable during + CSleep mode + 27 + 1 + + + USB2OTGHSULPILPEN + USB_PHY2 clocks enable during CSleep + mode + 28 + 1 + + + + + C1_AHB1LPENR + C1_AHB1LPENR + RCC AHB1 Sleep Clock Register + 0x160 + 0x20 + read-write + 0x00000000 + + + DMA1LPEN + DMA1 Clock Enable During CSleep + Mode + 0 + 1 + + + DMA2LPEN + DMA2 Clock Enable During CSleep + Mode + 1 + 1 + + + ADC12LPEN + ADC1/2 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + ETH1MACLPEN + Ethernet MAC bus interface Clock Enable + During CSleep Mode + 15 + 1 + + + ETH1TXLPEN + Ethernet Transmission Clock Enable + During CSleep Mode + 16 + 1 + + + ETH1RXLPEN + Ethernet Reception Clock Enable During + CSleep Mode + 17 + 1 + + + USB1OTGLPEN + USB1OTG peripheral clock enable during + CSleep mode + 25 + 1 + + + USB1ULPILPEN + USB_PHY1 clock enable during CSleep + mode + 26 + 1 + + + USB2OTGLPEN + USB2OTG peripheral clock enable during + CSleep mode + 27 + 1 + + + USB2ULPILPEN + USB_PHY2 clocks enable during CSleep + mode + 28 + 1 + + + + + C1_AHB2LPENR + C1_AHB2LPENR + RCC AHB2 Sleep Clock Register + 0x164 + 0x20 + read-write + 0x00000000 + + + CAMITFLPEN + CAMITF peripheral clock enable during + CSleep mode + 0 + 1 + + + CRYPTLPEN + CRYPT peripheral clock enable during + CSleep mode + 4 + 1 + + + HASHLPEN + HASH peripheral clock enable during + CSleep mode + 5 + 1 + + + SDMMC2LPEN + SDMMC2 and SDMMC2 Delay Clock Enable + During CSleep Mode + 9 + 1 + + + RNGLPEN + RNG peripheral clock enable during + CSleep mode + 6 + 1 + + + SRAM1LPEN + SRAM1 Clock Enable During CSleep + Mode + 29 + 1 + + + SRAM2LPEN + SRAM2 Clock Enable During CSleep + Mode + 30 + 1 + + + SRAM3LPEN + SRAM3 Clock Enable During CSleep + Mode + 31 + 1 + + + + + AHB2LPENR + AHB2LPENR + RCC AHB2 Sleep Clock Register + 0x104 + 0x20 + read-write + 0x00000000 + + + CAMITFLPEN + CAMITF peripheral clock enable during + CSleep mode + 0 + 1 + + + CRYPTLPEN + CRYPT peripheral clock enable during + CSleep mode + 4 + 1 + + + HASHLPEN + HASH peripheral clock enable during + CSleep mode + 5 + 1 + + + SDMMC2LPEN + SDMMC2 and SDMMC2 Delay Clock Enable + During CSleep Mode + 9 + 1 + + + RNGLPEN + RNG peripheral clock enable during + CSleep mode + 6 + 1 + + + SRAM1LPEN + SRAM1 Clock Enable During CSleep + Mode + 29 + 1 + + + SRAM2LPEN + SRAM2 Clock Enable During CSleep + Mode + 30 + 1 + + + SRAM3LPEN + SRAM3 Clock Enable During CSleep + Mode + 31 + 1 + + + + + AHB4LPENR + AHB4LPENR + RCC AHB4 Sleep Clock Register + 0x108 + 0x20 + read-write + 0x00000000 + + + GPIOALPEN + GPIO peripheral clock enable during + CSleep mode + 0 + 1 + + + GPIOBLPEN + GPIO peripheral clock enable during + CSleep mode + 1 + 1 + + + GPIOCLPEN + GPIO peripheral clock enable during + CSleep mode + 2 + 1 + + + GPIODLPEN + GPIO peripheral clock enable during + CSleep mode + 3 + 1 + + + GPIOELPEN + GPIO peripheral clock enable during + CSleep mode + 4 + 1 + + + GPIOFLPEN + GPIO peripheral clock enable during + CSleep mode + 5 + 1 + + + GPIOGLPEN + GPIO peripheral clock enable during + CSleep mode + 6 + 1 + + + GPIOHLPEN + GPIO peripheral clock enable during + CSleep mode + 7 + 1 + + + GPIOILPEN + GPIO peripheral clock enable during + CSleep mode + 8 + 1 + + + GPIOJLPEN + GPIO peripheral clock enable during + CSleep mode + 9 + 1 + + + GPIOKLPEN + GPIO peripheral clock enable during + CSleep mode + 10 + 1 + + + CRCLPEN + CRC peripheral clock enable during + CSleep mode + 19 + 1 + + + BDMALPEN + BDMA Clock Enable During CSleep + Mode + 21 + 1 + + + ADC3LPEN + ADC3 Peripheral Clocks Enable During + CSleep Mode + 24 + 1 + + + BKPRAMLPEN + Backup RAM Clock Enable During CSleep + Mode + 28 + 1 + + + SRAM4LPEN + SRAM4 Clock Enable During CSleep + Mode + 29 + 1 + + + + + C1_AHB4LPENR + C1_AHB4LPENR + RCC AHB4 Sleep Clock Register + 0x168 + 0x20 + read-write + 0x00000000 + + + GPIOALPEN + GPIO peripheral clock enable during + CSleep mode + 0 + 1 + + + GPIOBLPEN + GPIO peripheral clock enable during + CSleep mode + 1 + 1 + + + GPIOCLPEN + GPIO peripheral clock enable during + CSleep mode + 2 + 1 + + + GPIODLPEN + GPIO peripheral clock enable during + CSleep mode + 3 + 1 + + + GPIOELPEN + GPIO peripheral clock enable during + CSleep mode + 4 + 1 + + + GPIOFLPEN + GPIO peripheral clock enable during + CSleep mode + 5 + 1 + + + GPIOGLPEN + GPIO peripheral clock enable during + CSleep mode + 6 + 1 + + + GPIOHLPEN + GPIO peripheral clock enable during + CSleep mode + 7 + 1 + + + GPIOILPEN + GPIO peripheral clock enable during + CSleep mode + 8 + 1 + + + GPIOJLPEN + GPIO peripheral clock enable during + CSleep mode + 9 + 1 + + + GPIOKLPEN + GPIO peripheral clock enable during + CSleep mode + 10 + 1 + + + CRCLPEN + CRC peripheral clock enable during + CSleep mode + 19 + 1 + + + BDMALPEN + BDMA Clock Enable During CSleep + Mode + 21 + 1 + + + ADC3LPEN + ADC3 Peripheral Clocks Enable During + CSleep Mode + 24 + 1 + + + BKPRAMLPEN + Backup RAM Clock Enable During CSleep + Mode + 28 + 1 + + + SRAM4LPEN + SRAM4 Clock Enable During CSleep + Mode + 29 + 1 + + + + + C1_APB3LPENR + C1_APB3LPENR + RCC APB3 Sleep Clock Register + 0x16C + 0x20 + read-write + 0x00000000 + + + LTDCLPEN + LTDC peripheral clock enable during + CSleep mode + 3 + 1 + + + WWDG1LPEN + WWDG1 Clock Enable During CSleep + Mode + 6 + 1 + + + + + APB3LPENR + APB3LPENR + RCC APB3 Sleep Clock Register + 0x10C + 0x20 + read-write + 0x00000000 + + + LTDCLPEN + LTDC peripheral clock enable during + CSleep mode + 3 + 1 + + + WWDG1LPEN + WWDG1 Clock Enable During CSleep + Mode + 6 + 1 + + + + + APB1LLPENR + APB1LLPENR + RCC APB1 Low Sleep Clock + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + TIM2LPEN + TIM2 peripheral clock enable during + CSleep mode + 0 + 1 + + + TIM3LPEN + TIM3 peripheral clock enable during + CSleep mode + 1 + 1 + + + TIM4LPEN + TIM4 peripheral clock enable during + CSleep mode + 2 + 1 + + + TIM5LPEN + TIM5 peripheral clock enable during + CSleep mode + 3 + 1 + + + TIM6LPEN + TIM6 peripheral clock enable during + CSleep mode + 4 + 1 + + + TIM7LPEN + TIM7 peripheral clock enable during + CSleep mode + 5 + 1 + + + TIM12LPEN + TIM12 peripheral clock enable during + CSleep mode + 6 + 1 + + + TIM13LPEN + TIM13 peripheral clock enable during + CSleep mode + 7 + 1 + + + TIM14LPEN + TIM14 peripheral clock enable during + CSleep mode + 8 + 1 + + + LPTIM1LPEN + LPTIM1 Peripheral Clocks Enable During + CSleep Mode + 9 + 1 + + + SPI2LPEN + SPI2 Peripheral Clocks Enable During + CSleep Mode + 14 + 1 + + + SPI3LPEN + SPI3 Peripheral Clocks Enable During + CSleep Mode + 15 + 1 + + + SPDIFRXLPEN + SPDIFRX Peripheral Clocks Enable During + CSleep Mode + 16 + 1 + + + USART2LPEN + USART2 Peripheral Clocks Enable During + CSleep Mode + 17 + 1 + + + USART3LPEN + USART3 Peripheral Clocks Enable During + CSleep Mode + 18 + 1 + + + UART4LPEN + UART4 Peripheral Clocks Enable During + CSleep Mode + 19 + 1 + + + UART5LPEN + UART5 Peripheral Clocks Enable During + CSleep Mode + 20 + 1 + + + I2C1LPEN + I2C1 Peripheral Clocks Enable During + CSleep Mode + 21 + 1 + + + I2C2LPEN + I2C2 Peripheral Clocks Enable During + CSleep Mode + 22 + 1 + + + I2C3LPEN + I2C3 Peripheral Clocks Enable During + CSleep Mode + 23 + 1 + + + HDMICECLPEN + HDMI-CEC Peripheral Clocks Enable During + CSleep Mode + 27 + 1 + + + DAC12LPEN + DAC1/2 peripheral clock enable during + CSleep mode + 29 + 1 + + + USART7LPEN + USART7 Peripheral Clocks Enable During + CSleep Mode + 30 + 1 + + + USART8LPEN + USART8 Peripheral Clocks Enable During + CSleep Mode + 31 + 1 + + + + + C1_APB1LLPENR + C1_APB1LLPENR + RCC APB1 Low Sleep Clock + Register + 0x170 + 0x20 + read-write + 0x00000000 + + + TIM2LPEN + TIM2 peripheral clock enable during + CSleep mode + 0 + 1 + + + TIM3LPEN + TIM3 peripheral clock enable during + CSleep mode + 1 + 1 + + + TIM4LPEN + TIM4 peripheral clock enable during + CSleep mode + 2 + 1 + + + TIM5LPEN + TIM5 peripheral clock enable during + CSleep mode + 3 + 1 + + + TIM6LPEN + TIM6 peripheral clock enable during + CSleep mode + 4 + 1 + + + TIM7LPEN + TIM7 peripheral clock enable during + CSleep mode + 5 + 1 + + + TIM12LPEN + TIM12 peripheral clock enable during + CSleep mode + 6 + 1 + + + TIM13LPEN + TIM13 peripheral clock enable during + CSleep mode + 7 + 1 + + + TIM14LPEN + TIM14 peripheral clock enable during + CSleep mode + 8 + 1 + + + LPTIM1LPEN + LPTIM1 Peripheral Clocks Enable During + CSleep Mode + 9 + 1 + + + SPI2LPEN + SPI2 Peripheral Clocks Enable During + CSleep Mode + 14 + 1 + + + SPI3LPEN + SPI3 Peripheral Clocks Enable During + CSleep Mode + 15 + 1 + + + SPDIFRXLPEN + SPDIFRX Peripheral Clocks Enable During + CSleep Mode + 16 + 1 + + + USART2LPEN + USART2 Peripheral Clocks Enable During + CSleep Mode + 17 + 1 + + + USART3LPEN + USART3 Peripheral Clocks Enable During + CSleep Mode + 18 + 1 + + + UART4LPEN + UART4 Peripheral Clocks Enable During + CSleep Mode + 19 + 1 + + + UART5LPEN + UART5 Peripheral Clocks Enable During + CSleep Mode + 20 + 1 + + + I2C1LPEN + I2C1 Peripheral Clocks Enable During + CSleep Mode + 21 + 1 + + + I2C2LPEN + I2C2 Peripheral Clocks Enable During + CSleep Mode + 22 + 1 + + + I2C3LPEN + I2C3 Peripheral Clocks Enable During + CSleep Mode + 23 + 1 + + + HDMICECLPEN + HDMI-CEC Peripheral Clocks Enable During + CSleep Mode + 27 + 1 + + + DAC12LPEN + DAC1/2 peripheral clock enable during + CSleep mode + 29 + 1 + + + USART7LPEN + USART7 Peripheral Clocks Enable During + CSleep Mode + 30 + 1 + + + USART8LPEN + USART8 Peripheral Clocks Enable During + CSleep Mode + 31 + 1 + + + + + C1_APB1HLPENR + C1_APB1HLPENR + RCC APB1 High Sleep Clock + Register + 0x174 + 0x20 + read-write + 0x00000000 + + + CRSLPEN + Clock Recovery System peripheral clock + enable during CSleep mode + 1 + 1 + + + SWPLPEN + SWPMI Peripheral Clocks Enable During + CSleep Mode + 2 + 1 + + + OPAMPLPEN + OPAMP peripheral clock enable during + CSleep mode + 4 + 1 + + + MDIOSLPEN + MDIOS peripheral clock enable during + CSleep mode + 5 + 1 + + + FDCANLPEN + FDCAN Peripheral Clocks Enable During + CSleep Mode + 8 + 1 + + + + + APB1HLPENR + APB1HLPENR + RCC APB1 High Sleep Clock + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + CRSLPEN + Clock Recovery System peripheral clock + enable during CSleep mode + 1 + 1 + + + SWPLPEN + SWPMI Peripheral Clocks Enable During + CSleep Mode + 2 + 1 + + + OPAMPLPEN + OPAMP peripheral clock enable during + CSleep mode + 4 + 1 + + + MDIOSLPEN + MDIOS peripheral clock enable during + CSleep mode + 5 + 1 + + + FDCANLPEN + FDCAN Peripheral Clocks Enable During + CSleep Mode + 8 + 1 + + + + + APB2LPENR + APB2LPENR + RCC APB2 Sleep Clock Register + 0x118 + 0x20 + read-write + 0x00000000 + + + TIM1LPEN + TIM1 peripheral clock enable during + CSleep mode + 0 + 1 + + + TIM8LPEN + TIM8 peripheral clock enable during + CSleep mode + 1 + 1 + + + USART1LPEN + USART1 Peripheral Clocks Enable During + CSleep Mode + 4 + 1 + + + USART6LPEN + USART6 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + SPI1LPEN + SPI1 Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + SPI4LPEN + SPI4 Peripheral Clocks Enable During + CSleep Mode + 13 + 1 + + + TIM15LPEN + TIM15 peripheral clock enable during + CSleep mode + 16 + 1 + + + TIM16LPEN + TIM16 peripheral clock enable during + CSleep mode + 17 + 1 + + + TIM17LPEN + TIM17 peripheral clock enable during + CSleep mode + 18 + 1 + + + SPI5LPEN + SPI5 Peripheral Clocks Enable During + CSleep Mode + 20 + 1 + + + SAI1LPEN + SAI1 Peripheral Clocks Enable During + CSleep Mode + 22 + 1 + + + SAI2LPEN + SAI2 Peripheral Clocks Enable During + CSleep Mode + 23 + 1 + + + SAI3LPEN + SAI3 Peripheral Clocks Enable During + CSleep Mode + 24 + 1 + + + DFSDM1LPEN + DFSDM1 Peripheral Clocks Enable During + CSleep Mode + 28 + 1 + + + HRTIMLPEN + HRTIM peripheral clock enable during + CSleep mode + 29 + 1 + + + + + C1_APB2LPENR + C1_APB2LPENR + RCC APB2 Sleep Clock Register + 0x178 + 0x20 + read-write + 0x00000000 + + + TIM1LPEN + TIM1 peripheral clock enable during + CSleep mode + 0 + 1 + + + TIM8LPEN + TIM8 peripheral clock enable during + CSleep mode + 1 + 1 + + + USART1LPEN + USART1 Peripheral Clocks Enable During + CSleep Mode + 4 + 1 + + + USART6LPEN + USART6 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + SPI1LPEN + SPI1 Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + SPI4LPEN + SPI4 Peripheral Clocks Enable During + CSleep Mode + 13 + 1 + + + TIM15LPEN + TIM15 peripheral clock enable during + CSleep mode + 16 + 1 + + + TIM16LPEN + TIM16 peripheral clock enable during + CSleep mode + 17 + 1 + + + TIM17LPEN + TIM17 peripheral clock enable during + CSleep mode + 18 + 1 + + + SPI5LPEN + SPI5 Peripheral Clocks Enable During + CSleep Mode + 20 + 1 + + + SAI1LPEN + SAI1 Peripheral Clocks Enable During + CSleep Mode + 22 + 1 + + + SAI2LPEN + SAI2 Peripheral Clocks Enable During + CSleep Mode + 23 + 1 + + + SAI3LPEN + SAI3 Peripheral Clocks Enable During + CSleep Mode + 24 + 1 + + + DFSDM1LPEN + DFSDM1 Peripheral Clocks Enable During + CSleep Mode + 28 + 1 + + + HRTIMLPEN + HRTIM peripheral clock enable during + CSleep mode + 29 + 1 + + + + + C1_APB4LPENR + C1_APB4LPENR + RCC APB4 Sleep Clock Register + 0x17C + 0x20 + read-write + 0x00000000 + + + SYSCFGLPEN + SYSCFG peripheral clock enable during + CSleep mode + 1 + 1 + + + LPUART1LPEN + LPUART1 Peripheral Clocks Enable During + CSleep Mode + 3 + 1 + + + SPI6LPEN + SPI6 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + I2C4LPEN + I2C4 Peripheral Clocks Enable During + CSleep Mode + 7 + 1 + + + LPTIM2LPEN + LPTIM2 Peripheral Clocks Enable During + CSleep Mode + 9 + 1 + + + LPTIM3LPEN + LPTIM3 Peripheral Clocks Enable During + CSleep Mode + 10 + 1 + + + LPTIM4LPEN + LPTIM4 Peripheral Clocks Enable During + CSleep Mode + 11 + 1 + + + LPTIM5LPEN + LPTIM5 Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + COMP12LPEN + COMP1/2 peripheral clock enable during + CSleep mode + 14 + 1 + + + VREFLPEN + VREF peripheral clock enable during + CSleep mode + 15 + 1 + + + RTCAPBLPEN + RTC APB Clock Enable During CSleep + Mode + 16 + 1 + + + SAI4LPEN + SAI4 Peripheral Clocks Enable During + CSleep Mode + 21 + 1 + + + + + APB4LPENR + APB4LPENR + RCC APB4 Sleep Clock Register + 0x11C + 0x20 + read-write + 0x00000000 + + + SYSCFGLPEN + SYSCFG peripheral clock enable during + CSleep mode + 1 + 1 + + + LPUART1LPEN + LPUART1 Peripheral Clocks Enable During + CSleep Mode + 3 + 1 + + + SPI6LPEN + SPI6 Peripheral Clocks Enable During + CSleep Mode + 5 + 1 + + + I2C4LPEN + I2C4 Peripheral Clocks Enable During + CSleep Mode + 7 + 1 + + + LPTIM2LPEN + LPTIM2 Peripheral Clocks Enable During + CSleep Mode + 9 + 1 + + + LPTIM3LPEN + LPTIM3 Peripheral Clocks Enable During + CSleep Mode + 10 + 1 + + + LPTIM4LPEN + LPTIM4 Peripheral Clocks Enable During + CSleep Mode + 11 + 1 + + + LPTIM5LPEN + LPTIM5 Peripheral Clocks Enable During + CSleep Mode + 12 + 1 + + + COMP12LPEN + COMP1/2 peripheral clock enable during + CSleep mode + 14 + 1 + + + VREFLPEN + VREF peripheral clock enable during + CSleep mode + 15 + 1 + + + RTCAPBLPEN + RTC APB Clock Enable During CSleep + Mode + 16 + 1 + + + SAI4LPEN + SAI4 Peripheral Clocks Enable During + CSleep Mode + 21 + 1 + + + + + + + LPTIM1 + Low power timer + LPTIM + 0x40002400 + + 0x0 + 0x400 + registers + + + LPTIM1 + LPTIM1 global interrupt + 93 + + + + ISR + ISR + Interrupt and Status Register + 0x0 + 0x20 + read-only + 0x00000000 + + + DOWN + Counter direction change up to + down + 6 + 1 + + + UP + Counter direction change down to + up + 5 + 1 + + + ARROK + Autoreload register update + OK + 4 + 1 + + + CMPOK + Compare register update OK + 3 + 1 + + + EXTTRIG + External trigger edge + event + 2 + 1 + + + ARRM + Autoreload match + 1 + 1 + + + CMPM + Compare match + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x4 + 0x20 + write-only + 0x00000000 + + + DOWNCF + Direction change to down Clear + Flag + 6 + 1 + + + UPCF + Direction change to UP Clear + Flag + 5 + 1 + + + ARROKCF + Autoreload register update OK Clear + Flag + 4 + 1 + + + CMPOKCF + Compare register update OK Clear + Flag + 3 + 1 + + + EXTTRIGCF + External trigger valid edge Clear + Flag + 2 + 1 + + + ARRMCF + Autoreload match Clear + Flag + 1 + 1 + + + CMPMCF + compare match Clear Flag + 0 + 1 + + + + + IER + IER + Interrupt Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + DOWNIE + Direction change to down Interrupt + Enable + 6 + 1 + + + UPIE + Direction change to UP Interrupt + Enable + 5 + 1 + + + ARROKIE + Autoreload register update OK Interrupt + Enable + 4 + 1 + + + CMPOKIE + Compare register update OK Interrupt + Enable + 3 + 1 + + + EXTTRIGIE + External trigger valid edge Interrupt + Enable + 2 + 1 + + + ARRMIE + Autoreload match Interrupt + Enable + 1 + 1 + + + CMPMIE + Compare match Interrupt + Enable + 0 + 1 + + + + + CFGR + CFGR + Configuration Register + 0xC + 0x20 + read-write + 0x00000000 + + + ENC + Encoder mode enable + 24 + 1 + + + COUNTMODE + counter mode enabled + 23 + 1 + + + PRELOAD + Registers update mode + 22 + 1 + + + WAVPOL + Waveform shape polarity + 21 + 1 + + + WAVE + Waveform shape + 20 + 1 + + + TIMOUT + Timeout enable + 19 + 1 + + + TRIGEN + Trigger enable and + polarity + 17 + 2 + + + TRIGSEL + Trigger selector + 13 + 3 + + + PRESC + Clock prescaler + 9 + 3 + + + TRGFLT + Configurable digital filter for + trigger + 6 + 2 + + + CKFLT + Configurable digital filter for external + clock + 3 + 2 + + + CKPOL + Clock Polarity + 1 + 2 + + + CKSEL + Clock selector + 0 + 1 + + + + + CR + CR + Control Register + 0x10 + 0x20 + read-write + 0x00000000 + + + ENABLE + LPTIM Enable + 0 + 1 + + + SNGSTRT + LPTIM start in single mode + 1 + 1 + + + CNTSTRT + Timer start in continuous + mode + 2 + 1 + + + COUNTRST + Counter reset + 3 + 1 + + + RSTARE + Reset after read enable + 4 + 1 + + + + + CMP + CMP + Compare Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CMP + Compare value + 0 + 16 + + + + + ARR + ARR + Autoreload Register + 0x18 + 0x20 + read-write + 0x00000001 + + + ARR + Auto reload value + 0 + 16 + + + + + CNT + CNT + Counter Register + 0x1C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 16 + + + + + CFGR2 + CFGR2 + LPTIM configuration register 2 + 0x24 + 0x20 + read-write + 0x00000000 + + + IN1SEL + LPTIM Input 1 selection + 0 + 2 + + + IN2SEL + LPTIM Input 2 selection + 4 + 2 + + + + + + + LPTIM2 + 0x58002400 + + LPTIM2 + LPTIM2 timer interrupt + 138 + + + + LPTIM3 + Low power timer + LPTIM + 0x58002800 + + 0x0 + 0x400 + registers + + + LPTIM3 + LPTIM2 timer interrupt + 139 + + + + ISR + ISR + Interrupt and Status Register + 0x0 + 0x20 + read-only + 0x00000000 + + + DOWN + Counter direction change up to + down + 6 + 1 + + + UP + Counter direction change down to + up + 5 + 1 + + + ARROK + Autoreload register update + OK + 4 + 1 + + + CMPOK + Compare register update OK + 3 + 1 + + + EXTTRIG + External trigger edge + event + 2 + 1 + + + ARRM + Autoreload match + 1 + 1 + + + CMPM + Compare match + 0 + 1 + + + + + ICR + ICR + Interrupt Clear Register + 0x4 + 0x20 + write-only + 0x00000000 + + + DOWNCF + Direction change to down Clear + Flag + 6 + 1 + + + UPCF + Direction change to UP Clear + Flag + 5 + 1 + + + ARROKCF + Autoreload register update OK Clear + Flag + 4 + 1 + + + CMPOKCF + Compare register update OK Clear + Flag + 3 + 1 + + + EXTTRIGCF + External trigger valid edge Clear + Flag + 2 + 1 + + + ARRMCF + Autoreload match Clear + Flag + 1 + 1 + + + CMPMCF + compare match Clear Flag + 0 + 1 + + + + + IER + IER + Interrupt Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + DOWNIE + Direction change to down Interrupt + Enable + 6 + 1 + + + UPIE + Direction change to UP Interrupt + Enable + 5 + 1 + + + ARROKIE + Autoreload register update OK Interrupt + Enable + 4 + 1 + + + CMPOKIE + Compare register update OK Interrupt + Enable + 3 + 1 + + + EXTTRIGIE + External trigger valid edge Interrupt + Enable + 2 + 1 + + + ARRMIE + Autoreload match Interrupt + Enable + 1 + 1 + + + CMPMIE + Compare match Interrupt + Enable + 0 + 1 + + + + + CFGR + CFGR + Configuration Register + 0xC + 0x20 + read-write + 0x00000000 + + + ENC + Encoder mode enable + 24 + 1 + + + COUNTMODE + counter mode enabled + 23 + 1 + + + PRELOAD + Registers update mode + 22 + 1 + + + WAVPOL + Waveform shape polarity + 21 + 1 + + + WAVE + Waveform shape + 20 + 1 + + + TIMOUT + Timeout enable + 19 + 1 + + + TRIGEN + Trigger enable and + polarity + 17 + 2 + + + TRIGSEL + Trigger selector + 13 + 3 + + + PRESC + Clock prescaler + 9 + 3 + + + TRGFLT + Configurable digital filter for + trigger + 6 + 2 + + + CKFLT + Configurable digital filter for external + clock + 3 + 2 + + + CKPOL + Clock Polarity + 1 + 2 + + + CKSEL + Clock selector + 0 + 1 + + + + + CR + CR + Control Register + 0x10 + 0x20 + read-write + 0x00000000 + + + ENABLE + LPTIM Enable + 0 + 1 + + + SNGSTRT + LPTIM start in single mode + 1 + 1 + + + CNTSTRT + Timer start in continuous + mode + 2 + 1 + + + COUNTRST + Counter reset + 3 + 1 + + + RSTARE + Reset after read enable + 4 + 1 + + + + + CMP + CMP + Compare Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CMP + Compare value + 0 + 16 + + + + + ARR + ARR + Autoreload Register + 0x18 + 0x20 + read-write + 0x00000001 + + + ARR + Auto reload value + 0 + 16 + + + + + CNT + CNT + Counter Register + 0x1C + 0x20 + read-only + 0x00000000 + + + CNT + Counter value + 0 + 16 + + + + + CFGR2 + CFGR2 + LPTIM configuration register 2 + 0x24 + 0x20 + read-write + 0x00000000 + + + IN1SEL + LPTIM Input 1 selection + 0 + 2 + + + + + + + LPTIM4 + 0x58002C00 + + ETH_WKUP + Ethernet wakeup through EXTI + 62 + + + LPTIM4 + LPTIM2 timer interrupt + 140 + + + + LPTIM5 + 0x58003000 + + LPTIM5 + LPTIM2 timer interrupt + 141 + + + + LPUART1 + LPUART1 + LPUART + 0x58000C00 + + 0x0 + 0x400 + registers + + + LPUART + LPUART global interrupt + 142 + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + RXFFIE + RXFIFO Full interrupt + enable + 31 + 1 + + + TXFEIE + TXFIFO empty interrupt + enable + 30 + 1 + + + FIFOEN + FIFO mode enable + 29 + 1 + + + M1 + Word length + 28 + 1 + + + DEAT + Driver Enable assertion + time + 21 + 5 + + + DEDT + Driver Enable deassertion + time + 16 + 5 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UESM + USART enable in Stop mode + 1 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD + Address of the USART node + 24 + 8 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + DATAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + STOP + STOP bits + 12 + 2 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + TXFTCFG + TXFIFO threshold + configuration + 29 + 3 + + + RXFTIE + RXFIFO threshold interrupt + enable + 28 + 1 + + + RXFTCFG + Receive FIFO threshold + configuration + 25 + 3 + + + TXFTIE + TXFIFO threshold interrupt + enable + 23 + 1 + + + WUFIE + Wakeup from Stop mode interrupt + enable + 22 + 1 + + + WUS + Wakeup from Stop mode interrupt flag + selection + 20 + 2 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + BRR + BRR + 0 + 20 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + TXFT + TXFIFO threshold flag + 27 + 1 + + + RXFT + RXFIFO threshold flag + 26 + 1 + + + RXFF + RXFIFO Full + 24 + 1 + + + TXFE + TXFIFO Empty + 23 + 1 + + + REACK + REACK + 22 + 1 + + + TEACK + TEACK + 21 + 1 + + + WUF + WUF + 20 + 1 + + + RWU + RWU + 19 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NE + NE + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + WUCF + Wakeup from Stop mode clear + flag + 20 + 1 + + + CMCF + Character match clear flag + 17 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + PRESC + PRESC + Prescaler register + 0x2C + 0x20 + read-write + 0x0000 + + + PRESCALER + Clock prescaler + 0 + 4 + + + + + + + SYSCFG + System configuration controller + SYSCFG + 0x58000400 + + 0x0 + 0x400 + registers + + + + PMCR + PMCR + peripheral mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + I2C1FMP + I2C1 Fm+ + 0 + 1 + + + I2C2FMP + I2C2 Fm+ + 1 + 1 + + + I2C3FMP + I2C3 Fm+ + 2 + 1 + + + I2C4FMP + I2C4 Fm+ + 3 + 1 + + + PB6FMP + PB(6) Fm+ + 4 + 1 + + + PB7FMP + PB(7) Fast Mode Plus + 5 + 1 + + + PB8FMP + PB(8) Fast Mode Plus + 6 + 1 + + + PB9FMP + PB(9) Fm+ + 7 + 1 + + + BOOSTE + Booster Enable + 8 + 1 + + + BOOSTVDDSEL + Analog switch supply voltage selection + 9 + 1 + + + EPIS + Ethernet PHY Interface + Selection + 21 + 3 + + + PA0SO + PA0 Switch Open + 24 + 1 + + + PA1SO + PA1 Switch Open + 25 + 1 + + + PC2SO + PC2 Switch Open + 26 + 1 + + + PC3SO + PC3 Switch Open + 27 + 1 + + + + + EXTICR1 + EXTICR1 + external interrupt configuration register + 1 + 0x8 + 0x20 + read-write + 0x0000 + + + EXTI3 + EXTI x configuration (x = 0 to + 3) + 12 + 4 + + + EXTI2 + EXTI x configuration (x = 0 to + 3) + 8 + 4 + + + EXTI1 + EXTI x configuration (x = 0 to + 3) + 4 + 4 + + + EXTI0 + EXTI x configuration (x = 0 to + 3) + 0 + 4 + + + + + EXTICR2 + EXTICR2 + external interrupt configuration register + 2 + 0xC + 0x20 + read-write + 0x0000 + + + EXTI7 + EXTI x configuration (x = 4 to + 7) + 12 + 4 + + + EXTI6 + EXTI x configuration (x = 4 to + 7) + 8 + 4 + + + EXTI5 + EXTI x configuration (x = 4 to + 7) + 4 + 4 + + + EXTI4 + EXTI x configuration (x = 4 to + 7) + 0 + 4 + + + + + EXTICR3 + EXTICR3 + external interrupt configuration register + 3 + 0x10 + 0x20 + read-write + 0x0000 + + + EXTI11 + EXTI x configuration (x = 8 to + 11) + 12 + 4 + + + EXTI10 + EXTI10 + 8 + 4 + + + EXTI9 + EXTI x configuration (x = 8 to + 11) + 4 + 4 + + + EXTI8 + EXTI x configuration (x = 8 to + 11) + 0 + 4 + + + + + EXTICR4 + EXTICR4 + external interrupt configuration register + 4 + 0x14 + 0x20 + read-write + 0x0000 + + + EXTI15 + EXTI x configuration (x = 12 to + 15) + 12 + 4 + + + EXTI14 + EXTI x configuration (x = 12 to + 15) + 8 + 4 + + + EXTI13 + EXTI x configuration (x = 12 to + 15) + 4 + 4 + + + EXTI12 + EXTI x configuration (x = 12 to + 15) + 0 + 4 + + + + + CCCSR + CCCSR + compensation cell control/status + register + 0x20 + 0x20 + read-write + 0x00000000 + + + EN + enable + 0 + 1 + + + CS + Code selection + 1 + 1 + + + READY + Compensation cell ready + flag + 8 + 1 + + + HSLV + High-speed at low-voltage + 16 + 1 + + + + + CCVR + CCVR + SYSCFG compensation cell value + register + 0x24 + 0x20 + read-only + 0x00000000 + + + NCV + NMOS compensation value + 0 + 4 + + + PCV + PMOS compensation value + 4 + 4 + + + + + CCCR + CCCR + SYSCFG compensation cell code + register + 0x28 + 0x20 + read-write + 0x00000000 + + + NCC + NMOS compensation code + 0 + 4 + + + PCC + PMOS compensation code + 4 + 4 + + + + + PWRCR + PWRCR + SYSCFG power control register + 0x2C + 0x20 + read-write + 0x00000000 + + + ODEN + Overdrive enable + 0 + 4 + + + + + + PKGR + PKGR + SYSCFG package register + 0x124 + 0x20 + read-only + 0x00000000 + + + PKG + Package + 0 + 4 + + + + + UR0 + UR0 + SYSCFG user register 0 + 0x300 + 0x20 + read-only + 0x00000000 + + + BKS + Bank Swap + 0 + 1 + + + RDP + Readout protection + 16 + 8 + + + + + UR2 + UR2 + SYSCFG user register 2 + 0x308 + 0x20 + read-write + 0x00000000 + + + BORH + BOR_LVL Brownout Reset Threshold + Level + 0 + 2 + + + BOOT_ADD0 + Boot Address 0 + 16 + 16 + + + + + UR3 + UR3 + SYSCFG user register 3 + 0x30C + 0x20 + read-write + 0x00000000 + + + BOOT_ADD1 + Boot Address 1 + 16 + 16 + + + + + UR4 + UR4 + SYSCFG user register 4 + 0x310 + 0x20 + read-only + 0x00000000 + + + MEPAD_1 + Mass Erase Protected Area Disabled for + bank 1 + 16 + 1 + + + + + UR5 + UR5 + SYSCFG user register 5 + 0x314 + 0x20 + read-only + 0x00000000 + + + MESAD_1 + Mass erase secured area disabled for + bank 1 + 0 + 1 + + + WRPN_1 + Write protection for flash bank + 1 + 16 + 8 + + + + + UR6 + UR6 + SYSCFG user register 6 + 0x318 + 0x20 + read-only + 0x00000000 + + + PA_BEG_1 + Protected area start address for bank + 1 + 0 + 12 + + + PA_END_1 + Protected area end address for bank + 1 + 16 + 12 + + + + + UR7 + UR7 + SYSCFG user register 7 + 0x31C + 0x20 + read-only + 0x00000000 + + + SA_BEG_1 + Secured area start address for bank + 1 + 0 + 12 + + + SA_END_1 + Secured area end address for bank + 1 + 16 + 12 + + + + + UR8 + UR8 + SYSCFG user register 8 + 0x320 + 0x20 + read-only + 0x00000000 + + + MEPAD_2 + Mass erase protected area disabled for + bank 2 + 0 + 1 + + + MESAD_2 + Mass erase secured area disabled for + bank 2 + 16 + 1 + + + + + UR9 + UR9 + SYSCFG user register 9 + 0x324 + 0x20 + read-only + 0x00000000 + + + WRPN_2 + Write protection for flash bank + 2 + 0 + 8 + + + PA_BEG_2 + Protected area start address for bank + 2 + 16 + 12 + + + + + UR10 + UR10 + SYSCFG user register 10 + 0x328 + 0x20 + read-only + 0x00000000 + + + PA_END_2 + Protected area end address for bank + 2 + 0 + 12 + + + SA_BEG_2 + Secured area start address for bank + 2 + 16 + 12 + + + + + UR11 + UR11 + SYSCFG user register 11 + 0x32C + 0x20 + read-only + 0x00000000 + + + SA_END_2 + Secured area end address for bank + 2 + 0 + 12 + + + IWDG1M + Independent Watchdog 1 + mode + 16 + 1 + + + + + UR12 + UR12 + SYSCFG user register 12 + 0x330 + 0x20 + read-only + 0x00000000 + + + SECURE + Secure mode + 16 + 1 + + + + + UR13 + UR13 + SYSCFG user register 13 + 0x334 + 0x20 + read-only + 0x00000000 + + + SDRS + Secured DTCM RAM Size + 0 + 2 + + + D1SBRST + D1 Standby reset + 16 + 1 + + + + + UR14 + UR14 + SYSCFG user register 14 + 0x338 + 0x20 + read-write + 0x00000000 + + + D1STPRST + D1 Stop Reset + 0 + 1 + + + + + UR15 + UR15 + SYSCFG user register 15 + 0x33C + 0x20 + read-only + 0x00000000 + + + FZIWDGSTB + Freeze independent watchdog in Standby + mode + 16 + 1 + + + + + UR16 + UR16 + SYSCFG user register 16 + 0x340 + 0x20 + read-only + 0x00000000 + + + FZIWDGSTP + Freeze independent watchdog in Stop + mode + 0 + 1 + + + PKP + Private key programmed + 16 + 1 + + + + + UR17 + UR17 + SYSCFG user register 17 + 0x344 + 0x20 + read-only + 0x00000000 + + + IO_HSLV + I/O high speed / low + voltage + 0 + 1 + + + + + + + EXTI + External interrupt/event + controller + EXTI + 0x58000000 + + 0x0 + 0x400 + registers + + + PVD_PVM + PVD through EXTI line + 1 + + + EXTI0 + EXTI Line 0 interrupt + 6 + + + EXTI1 + EXTI Line 1 interrupt + 7 + + + EXTI2 + EXTI Line 2 interrupt + 8 + + + EXTI3 + EXTI Line 3interrupt + 9 + + + EXTI4 + EXTI Line 4interrupt + 10 + + + EXTI9_5 + EXTI Line[9:5] interrupts + 23 + + + EXTI15_10 + EXTI Line[15:10] interrupts + 40 + + + RTC_ALARM + RTC alarms (A and B) + 41 + + + + RTSR1 + RTSR1 + EXTI rising trigger selection + register + 0x0 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration bit + of Configurable Event input + 0 + 1 + + + TR1 + Rising trigger event configuration bit + of Configurable Event input + 1 + 1 + + + TR2 + Rising trigger event configuration bit + of Configurable Event input + 2 + 1 + + + TR3 + Rising trigger event configuration bit + of Configurable Event input + 3 + 1 + + + TR4 + Rising trigger event configuration bit + of Configurable Event input + 4 + 1 + + + TR5 + Rising trigger event configuration bit + of Configurable Event input + 5 + 1 + + + TR6 + Rising trigger event configuration bit + of Configurable Event input + 6 + 1 + + + TR7 + Rising trigger event configuration bit + of Configurable Event input + 7 + 1 + + + TR8 + Rising trigger event configuration bit + of Configurable Event input + 8 + 1 + + + TR9 + Rising trigger event configuration bit + of Configurable Event input + 9 + 1 + + + TR10 + Rising trigger event configuration bit + of Configurable Event input + 10 + 1 + + + TR11 + Rising trigger event configuration bit + of Configurable Event input + 11 + 1 + + + TR12 + Rising trigger event configuration bit + of Configurable Event input + 12 + 1 + + + TR13 + Rising trigger event configuration bit + of Configurable Event input + 13 + 1 + + + TR14 + Rising trigger event configuration bit + of Configurable Event input + 14 + 1 + + + TR15 + Rising trigger event configuration bit + of Configurable Event input + 15 + 1 + + + TR16 + Rising trigger event configuration bit + of Configurable Event input + 16 + 1 + + + TR17 + Rising trigger event configuration bit + of Configurable Event input + 17 + 1 + + + TR18 + Rising trigger event configuration bit + of Configurable Event input + 18 + 1 + + + TR19 + Rising trigger event configuration bit + of Configurable Event input + 19 + 1 + + + TR20 + Rising trigger event configuration bit + of Configurable Event input + 20 + 1 + + + TR21 + Rising trigger event configuration bit + of Configurable Event input + 21 + 1 + + + + + FTSR1 + FTSR1 + EXTI falling trigger selection + register + 0x4 + 0x20 + read-write + 0x00000000 + + + TR0 + Rising trigger event configuration bit + of Configurable Event input + 0 + 1 + + + TR1 + Rising trigger event configuration bit + of Configurable Event input + 1 + 1 + + + TR2 + Rising trigger event configuration bit + of Configurable Event input + 2 + 1 + + + TR3 + Rising trigger event configuration bit + of Configurable Event input + 3 + 1 + + + TR4 + Rising trigger event configuration bit + of Configurable Event input + 4 + 1 + + + TR5 + Rising trigger event configuration bit + of Configurable Event input + 5 + 1 + + + TR6 + Rising trigger event configuration bit + of Configurable Event input + 6 + 1 + + + TR7 + Rising trigger event configuration bit + of Configurable Event input + 7 + 1 + + + TR8 + Rising trigger event configuration bit + of Configurable Event input + 8 + 1 + + + TR9 + Rising trigger event configuration bit + of Configurable Event input + 9 + 1 + + + TR10 + Rising trigger event configuration bit + of Configurable Event input + 10 + 1 + + + TR11 + Rising trigger event configuration bit + of Configurable Event input + 11 + 1 + + + TR12 + Rising trigger event configuration bit + of Configurable Event input + 12 + 1 + + + TR13 + Rising trigger event configuration bit + of Configurable Event input + 13 + 1 + + + TR14 + Rising trigger event configuration bit + of Configurable Event input + 14 + 1 + + + TR15 + Rising trigger event configuration bit + of Configurable Event input + 15 + 1 + + + TR16 + Rising trigger event configuration bit + of Configurable Event input + 16 + 1 + + + TR17 + Rising trigger event configuration bit + of Configurable Event input + 17 + 1 + + + TR18 + Rising trigger event configuration bit + of Configurable Event input + 18 + 1 + + + TR19 + Rising trigger event configuration bit + of Configurable Event input + 19 + 1 + + + TR20 + Rising trigger event configuration bit + of Configurable Event input + 20 + 1 + + + TR21 + Rising trigger event configuration bit + of Configurable Event input + 21 + 1 + + + + + SWIER1 + SWIER1 + EXTI software interrupt event + register + 0x8 + 0x20 + read-write + 0x00000000 + + + SWIER0 + Rising trigger event configuration bit + of Configurable Event input + 0 + 1 + + + SWIER1 + Rising trigger event configuration bit + of Configurable Event input + 1 + 1 + + + SWIER2 + Rising trigger event configuration bit + of Configurable Event input + 2 + 1 + + + SWIER3 + Rising trigger event configuration bit + of Configurable Event input + 3 + 1 + + + SWIER4 + Rising trigger event configuration bit + of Configurable Event input + 4 + 1 + + + SWIER5 + Rising trigger event configuration bit + of Configurable Event input + 5 + 1 + + + SWIER6 + Rising trigger event configuration bit + of Configurable Event input + 6 + 1 + + + SWIER7 + Rising trigger event configuration bit + of Configurable Event input + 7 + 1 + + + SWIER8 + Rising trigger event configuration bit + of Configurable Event input + 8 + 1 + + + SWIER9 + Rising trigger event configuration bit + of Configurable Event input + 9 + 1 + + + SWIER10 + Rising trigger event configuration bit + of Configurable Event input + 10 + 1 + + + SWIER11 + Rising trigger event configuration bit + of Configurable Event input + 11 + 1 + + + SWIER12 + Rising trigger event configuration bit + of Configurable Event input + 12 + 1 + + + SWIER13 + Rising trigger event configuration bit + of Configurable Event input + 13 + 1 + + + SWIER14 + Rising trigger event configuration bit + of Configurable Event input + 14 + 1 + + + SWIER15 + Rising trigger event configuration bit + of Configurable Event input + 15 + 1 + + + SWIER16 + Rising trigger event configuration bit + of Configurable Event input + 16 + 1 + + + SWIER17 + Rising trigger event configuration bit + of Configurable Event input + 17 + 1 + + + SWIER18 + Rising trigger event configuration bit + of Configurable Event input + 18 + 1 + + + SWIER19 + Rising trigger event configuration bit + of Configurable Event input + 19 + 1 + + + SWIER20 + Rising trigger event configuration bit + of Configurable Event input + 20 + 1 + + + SWIER21 + Rising trigger event configuration bit + of Configurable Event input + 21 + 1 + + + + + D3PMR1 + D3PMR1 + EXTI D3 pending mask register + 0xC + 0x20 + read-write + 0x00000000 + + + MR0 + Rising trigger event configuration bit + of Configurable Event input + 0 + 1 + + + MR1 + Rising trigger event configuration bit + of Configurable Event input + 1 + 1 + + + MR2 + Rising trigger event configuration bit + of Configurable Event input + 2 + 1 + + + MR3 + Rising trigger event configuration bit + of Configurable Event input + 3 + 1 + + + MR4 + Rising trigger event configuration bit + of Configurable Event input + 4 + 1 + + + MR5 + Rising trigger event configuration bit + of Configurable Event input + 5 + 1 + + + MR6 + Rising trigger event configuration bit + of Configurable Event input + 6 + 1 + + + MR7 + Rising trigger event configuration bit + of Configurable Event input + 7 + 1 + + + MR8 + Rising trigger event configuration bit + of Configurable Event input + 8 + 1 + + + MR9 + Rising trigger event configuration bit + of Configurable Event input + 9 + 1 + + + MR10 + Rising trigger event configuration bit + of Configurable Event input + 10 + 1 + + + MR11 + Rising trigger event configuration bit + of Configurable Event input + 11 + 1 + + + MR12 + Rising trigger event configuration bit + of Configurable Event input + 12 + 1 + + + MR13 + Rising trigger event configuration bit + of Configurable Event input + 13 + 1 + + + MR14 + Rising trigger event configuration bit + of Configurable Event input + 14 + 1 + + + MR15 + Rising trigger event configuration bit + of Configurable Event input + 15 + 1 + + + MR19 + Rising trigger event configuration bit + of Configurable Event input + 19 + 1 + + + MR20 + Rising trigger event configuration bit + of Configurable Event input + 20 + 1 + + + MR21 + Rising trigger event configuration bit + of Configurable Event input + 21 + 1 + + + MR25 + Rising trigger event configuration bit + of Configurable Event input + 25 + 1 + + + + + D3PCR1L + D3PCR1L + EXTI D3 pending clear selection register + low + 0x10 + 0x20 + read-write + 0x00000000 + + + PCS0 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 0 + 2 + + + PCS1 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 2 + 2 + + + PCS2 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 4 + 2 + + + PCS3 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 6 + 2 + + + PCS4 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 8 + 2 + + + PCS5 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 10 + 2 + + + PCS6 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 12 + 2 + + + PCS7 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 14 + 2 + + + PCS8 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 16 + 2 + + + PCS9 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 18 + 2 + + + PCS10 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 20 + 2 + + + PCS11 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 22 + 2 + + + PCS12 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 24 + 2 + + + PCS13 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 26 + 2 + + + PCS14 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 28 + 2 + + + PCS15 + D3 Pending request clear input signal + selection on Event input x = truncate + (n/2) + 30 + 2 + + + + + D3PCR1H + D3PCR1H + EXTI D3 pending clear selection register + high + 0x14 + 0x20 + read-write + 0x00000000 + + + PCS19 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+32)/2) + 6 + 2 + + + PCS20 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+32)/2) + 8 + 2 + + + PCS21 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+32)/2) + 10 + 2 + + + PCS25 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+32)/2) + 18 + 2 + + + + + RTSR2 + RTSR2 + EXTI rising trigger selection + register + 0x20 + 0x20 + read-write + 0x00000000 + + + TR49 + Rising trigger event configuration bit + of Configurable Event input x+32 + 17 + 1 + + + TR51 + Rising trigger event configuration bit + of Configurable Event input x+32 + 19 + 1 + + + + + FTSR2 + FTSR2 + EXTI falling trigger selection + register + 0x24 + 0x20 + read-write + 0x00000000 + + + TR49 + Falling trigger event configuration bit + of Configurable Event input x+32 + 17 + 1 + + + TR51 + Falling trigger event configuration bit + of Configurable Event input x+32 + 19 + 1 + + + + + SWIER2 + SWIER2 + EXTI software interrupt event + register + 0x28 + 0x20 + read-write + 0x00000000 + + + SWIER49 + Software interrupt on line + x+32 + 17 + 1 + + + SWIER51 + Software interrupt on line + x+32 + 19 + 1 + + + + + D3PMR2 + D3PMR2 + EXTI D3 pending mask register + 0x2C + 0x20 + read-write + 0x00000000 + + + MR34 + D3 Pending Mask on Event input + x+32 + 2 + 1 + + + MR35 + D3 Pending Mask on Event input + x+32 + 3 + 1 + + + MR41 + D3 Pending Mask on Event input + x+32 + 9 + 1 + + + MR48 + D3 Pending Mask on Event input + x+32 + 16 + 1 + + + MR49 + D3 Pending Mask on Event input + x+32 + 17 + 1 + + + MR50 + D3 Pending Mask on Event input + x+32 + 18 + 1 + + + MR51 + D3 Pending Mask on Event input + x+32 + 19 + 1 + + + MR52 + D3 Pending Mask on Event input + x+32 + 20 + 1 + + + MR53 + D3 Pending Mask on Event input + x+32 + 21 + 1 + + + + + D3PCR2L + D3PCR2L + EXTI D3 pending clear selection register + low + 0x30 + 0x20 + read-write + 0x00000000 + + + PCS35 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+64)/2) + 6 + 2 + + + PCS34 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+64)/2) + 4 + 2 + + + PCS41 + D3 Pending request clear input signal + selection on Event input x = truncate + ((n+64)/2) + 18 + 2 + + + + + D3PCR2H + D3PCR2H + EXTI D3 pending clear selection register + high + 0x34 + 0x20 + read-write + 0x00000000 + + + PCS48 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 0 + 2 + + + PCS49 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 2 + 2 + + + PCS50 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 4 + 2 + + + PCS51 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 6 + 2 + + + PCS52 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 8 + 2 + + + PCS53 + Pending request clear input signal + selection on Event input x= truncate + ((n+96)/2) + 10 + 2 + + + + + RTSR3 + RTSR3 + EXTI rising trigger selection + register + 0x40 + 0x20 + read-write + 0x00000000 + + + TR82 + Rising trigger event configuration bit + of Configurable Event input x+64 + 18 + 1 + + + TR84 + Rising trigger event configuration bit + of Configurable Event input x+64 + 20 + 1 + + + TR85 + Rising trigger event configuration bit + of Configurable Event input x+64 + 21 + 1 + + + TR86 + Rising trigger event configuration bit + of Configurable Event input x+64 + 22 + 1 + + + + + FTSR3 + FTSR3 + EXTI falling trigger selection + register + 0x44 + 0x20 + read-write + 0x00000000 + + + TR82 + Falling trigger event configuration bit + of Configurable Event input x+64 + 18 + 1 + + + TR84 + Falling trigger event configuration bit + of Configurable Event input x+64 + 20 + 1 + + + TR85 + Falling trigger event configuration bit + of Configurable Event input x+64 + 21 + 1 + + + TR86 + Falling trigger event configuration bit + of Configurable Event input x+64 + 22 + 1 + + + + + SWIER3 + SWIER3 + EXTI software interrupt event + register + 0x48 + 0x20 + read-write + 0x00000000 + + + SWIER82 + Software interrupt on line + x+64 + 18 + 1 + + + SWIER84 + Software interrupt on line + x+64 + 20 + 1 + + + SWIER85 + Software interrupt on line + x+64 + 21 + 1 + + + SWIER86 + Software interrupt on line + x+64 + 22 + 1 + + + + + D3PMR3 + D3PMR3 + EXTI D3 pending mask register + 0x4C + 0x20 + read-write + 0x00000000 + + + MR88 + D3 Pending Mask on Event input + x+64 + 24 + 1 + + + + + D3PCR3H + D3PCR3H + EXTI D3 pending clear selection register + high + 0x54 + 0x20 + read-write + 0x00000000 + + + PCS88 + D3 Pending request clear input signal + selection on Event input x= truncate + N+160/2 + 18 + 2 + + + + + CPUIMR1 + CPUIMR1 + EXTI interrupt mask register + 0x80 + 0x20 + read-write + 0xFFC00000 + + + MR0 + Rising trigger event configuration bit + of Configurable Event input + 0 + 1 + + + MR1 + Rising trigger event configuration bit + of Configurable Event input + 1 + 1 + + + MR2 + Rising trigger event configuration bit + of Configurable Event input + 2 + 1 + + + MR3 + Rising trigger event configuration bit + of Configurable Event input + 3 + 1 + + + MR4 + Rising trigger event configuration bit + of Configurable Event input + 4 + 1 + + + MR5 + Rising trigger event configuration bit + of Configurable Event input + 5 + 1 + + + MR6 + Rising trigger event configuration bit + of Configurable Event input + 6 + 1 + + + MR7 + Rising trigger event configuration bit + of Configurable Event input + 7 + 1 + + + MR8 + Rising trigger event configuration bit + of Configurable Event input + 8 + 1 + + + MR9 + Rising trigger event configuration bit + of Configurable Event input + 9 + 1 + + + MR10 + Rising trigger event configuration bit + of Configurable Event input + 10 + 1 + + + MR11 + Rising trigger event configuration bit + of Configurable Event input + 11 + 1 + + + MR12 + Rising trigger event configuration bit + of Configurable Event input + 12 + 1 + + + MR13 + Rising trigger event configuration bit + of Configurable Event input + 13 + 1 + + + MR14 + Rising trigger event configuration bit + of Configurable Event input + 14 + 1 + + + MR15 + Rising trigger event configuration bit + of Configurable Event input + 15 + 1 + + + MR16 + Rising trigger event configuration bit + of Configurable Event input + 16 + 1 + + + MR17 + Rising trigger event configuration bit + of Configurable Event input + 17 + 1 + + + MR18 + Rising trigger event configuration bit + of Configurable Event input + 18 + 1 + + + MR19 + Rising trigger event configuration bit + of Configurable Event input + 19 + 1 + + + MR20 + Rising trigger event configuration bit + of Configurable Event input + 20 + 1 + + + MR21 + Rising trigger event configuration bit + of Configurable Event input + 21 + 1 + + + MR22 + Rising trigger event configuration bit + of Configurable Event input + 22 + 1 + + + MR23 + Rising trigger event configuration bit + of Configurable Event input + 23 + 1 + + + MR24 + Rising trigger event configuration bit + of Configurable Event input + 24 + 1 + + + MR25 + Rising trigger event configuration bit + of Configurable Event input + 25 + 1 + + + MR26 + Rising trigger event configuration bit + of Configurable Event input + 26 + 1 + + + MR27 + Rising trigger event configuration bit + of Configurable Event input + 27 + 1 + + + MR28 + Rising trigger event configuration bit + of Configurable Event input + 28 + 1 + + + MR29 + Rising trigger event configuration bit + of Configurable Event input + 29 + 1 + + + MR30 + Rising trigger event configuration bit + of Configurable Event input + 30 + 1 + + + MR31 + Rising trigger event configuration bit + of Configurable Event input + 31 + 1 + + + + + CPUEMR1 + CPUEMR1 + EXTI event mask register + 0x84 + 0x20 + read-write + 0x00000000 + + + MR0 + CPU Event mask on Event input + x + 0 + 1 + + + MR1 + CPU Event mask on Event input + x + 1 + 1 + + + MR2 + CPU Event mask on Event input + x + 2 + 1 + + + MR3 + CPU Event mask on Event input + x + 3 + 1 + + + MR4 + CPU Event mask on Event input + x + 4 + 1 + + + MR5 + CPU Event mask on Event input + x + 5 + 1 + + + MR6 + CPU Event mask on Event input + x + 6 + 1 + + + MR7 + CPU Event mask on Event input + x + 7 + 1 + + + MR8 + CPU Event mask on Event input + x + 8 + 1 + + + MR9 + CPU Event mask on Event input + x + 9 + 1 + + + MR10 + CPU Event mask on Event input + x + 10 + 1 + + + MR11 + CPU Event mask on Event input + x + 11 + 1 + + + MR12 + CPU Event mask on Event input + x + 12 + 1 + + + MR13 + CPU Event mask on Event input + x + 13 + 1 + + + MR14 + CPU Event mask on Event input + x + 14 + 1 + + + MR15 + CPU Event mask on Event input + x + 15 + 1 + + + MR16 + CPU Event mask on Event input + x + 16 + 1 + + + MR17 + CPU Event mask on Event input + x + 17 + 1 + + + MR18 + CPU Event mask on Event input + x + 18 + 1 + + + MR19 + CPU Event mask on Event input + x + 19 + 1 + + + MR20 + CPU Event mask on Event input + x + 20 + 1 + + + MR21 + CPU Event mask on Event input + x + 21 + 1 + + + MR22 + CPU Event mask on Event input + x + 22 + 1 + + + MR23 + CPU Event mask on Event input + x + 23 + 1 + + + MR24 + CPU Event mask on Event input + x + 24 + 1 + + + MR25 + CPU Event mask on Event input + x + 25 + 1 + + + MR26 + CPU Event mask on Event input + x + 26 + 1 + + + MR27 + CPU Event mask on Event input + x + 27 + 1 + + + MR28 + CPU Event mask on Event input + x + 28 + 1 + + + MR29 + CPU Event mask on Event input + x + 29 + 1 + + + MR30 + CPU Event mask on Event input + x + 30 + 1 + + + MR31 + CPU Event mask on Event input + x + 31 + 1 + + + + + CPUPR1 + CPUPR1 + EXTI pending register + 0x88 + 0x20 + read-write + 0x00000000 + + + PR0 + CPU Event mask on Event input + x + 0 + 1 + + + PR1 + CPU Event mask on Event input + x + 1 + 1 + + + PR2 + CPU Event mask on Event input + x + 2 + 1 + + + PR3 + CPU Event mask on Event input + x + 3 + 1 + + + PR4 + CPU Event mask on Event input + x + 4 + 1 + + + PR5 + CPU Event mask on Event input + x + 5 + 1 + + + PR6 + CPU Event mask on Event input + x + 6 + 1 + + + PR7 + CPU Event mask on Event input + x + 7 + 1 + + + PR8 + CPU Event mask on Event input + x + 8 + 1 + + + PR9 + CPU Event mask on Event input + x + 9 + 1 + + + PR10 + CPU Event mask on Event input + x + 10 + 1 + + + PR11 + CPU Event mask on Event input + x + 11 + 1 + + + PR12 + CPU Event mask on Event input + x + 12 + 1 + + + PR13 + CPU Event mask on Event input + x + 13 + 1 + + + PR14 + CPU Event mask on Event input + x + 14 + 1 + + + PR15 + CPU Event mask on Event input + x + 15 + 1 + + + PR16 + CPU Event mask on Event input + x + 16 + 1 + + + PR17 + CPU Event mask on Event input + x + 17 + 1 + + + PR18 + CPU Event mask on Event input + x + 18 + 1 + + + PR19 + CPU Event mask on Event input + x + 19 + 1 + + + PR20 + CPU Event mask on Event input + x + 20 + 1 + + + PR21 + CPU Event mask on Event input + x + 21 + 1 + + + + + CPUIMR2 + CPUIMR2 + EXTI interrupt mask register + 0x90 + 0x20 + read-write + 0x00000000 + + + MR0 + CPU Interrupt Mask on Direct Event input + x+32 + 0 + 1 + + + MR1 + CPU Interrupt Mask on Direct Event input + x+32 + 1 + 1 + + + MR2 + CPU Interrupt Mask on Direct Event input + x+32 + 2 + 1 + + + MR3 + CPU Interrupt Mask on Direct Event input + x+32 + 3 + 1 + + + MR4 + CPU Interrupt Mask on Direct Event input + x+32 + 4 + 1 + + + MR5 + CPU Interrupt Mask on Direct Event input + x+32 + 5 + 1 + + + MR6 + CPU Interrupt Mask on Direct Event input + x+32 + 6 + 1 + + + MR7 + CPU Interrupt Mask on Direct Event input + x+32 + 7 + 1 + + + MR8 + CPU Interrupt Mask on Direct Event input + x+32 + 8 + 1 + + + MR9 + CPU Interrupt Mask on Direct Event input + x+32 + 9 + 1 + + + MR10 + CPU Interrupt Mask on Direct Event input + x+32 + 10 + 1 + + + MR11 + CPU Interrupt Mask on Direct Event input + x+32 + 11 + 1 + + + MR12 + CPU Interrupt Mask on Direct Event input + x+32 + 12 + 1 + + + MR14 + CPU Interrupt Mask on Direct Event input + x+32 + 14 + 1 + + + MR15 + CPU Interrupt Mask on Direct Event input + x+32 + 15 + 1 + + + MR16 + CPU Interrupt Mask on Direct Event input + x+32 + 16 + 1 + + + MR17 + CPU Interrupt Mask on Direct Event input + x+32 + 17 + 1 + + + MR18 + CPU Interrupt Mask on Direct Event input + x+32 + 18 + 1 + + + MR19 + CPU Interrupt Mask on Direct Event input + x+32 + 19 + 1 + + + MR20 + CPU Interrupt Mask on Direct Event input + x+32 + 20 + 1 + + + MR21 + CPU Interrupt Mask on Direct Event input + x+32 + 21 + 1 + + + MR22 + CPU Interrupt Mask on Direct Event input + x+32 + 22 + 1 + + + MR23 + CPU Interrupt Mask on Direct Event input + x+32 + 23 + 1 + + + MR24 + CPU Interrupt Mask on Direct Event input + x+32 + 24 + 1 + + + MR25 + CPU Interrupt Mask on Direct Event input + x+32 + 25 + 1 + + + MR26 + CPU Interrupt Mask on Direct Event input + x+32 + 26 + 1 + + + MR27 + CPU Interrupt Mask on Direct Event input + x+32 + 27 + 1 + + + MR28 + CPU Interrupt Mask on Direct Event input + x+32 + 28 + 1 + + + MR29 + CPU Interrupt Mask on Direct Event input + x+32 + 29 + 1 + + + MR30 + CPU Interrupt Mask on Direct Event input + x+32 + 30 + 1 + + + MR31 + CPU Interrupt Mask on Direct Event input + x+32 + 31 + 1 + + + + + CPUEMR2 + CPUEMR2 + EXTI event mask register + 0x94 + 0x20 + read-write + 0x00000000 + + + MR32 + CPU Interrupt Mask on Direct Event input + x+32 + 0 + 1 + + + MR33 + CPU Interrupt Mask on Direct Event input + x+32 + 1 + 1 + + + MR34 + CPU Interrupt Mask on Direct Event input + x+32 + 2 + 1 + + + MR35 + CPU Interrupt Mask on Direct Event input + x+32 + 3 + 1 + + + MR36 + CPU Interrupt Mask on Direct Event input + x+32 + 4 + 1 + + + MR37 + CPU Interrupt Mask on Direct Event input + x+32 + 5 + 1 + + + MR38 + CPU Interrupt Mask on Direct Event input + x+32 + 6 + 1 + + + MR39 + CPU Interrupt Mask on Direct Event input + x+32 + 7 + 1 + + + MR40 + CPU Interrupt Mask on Direct Event input + x+32 + 8 + 1 + + + MR41 + CPU Interrupt Mask on Direct Event input + x+32 + 9 + 1 + + + MR42 + CPU Interrupt Mask on Direct Event input + x+32 + 10 + 1 + + + MR43 + CPU Interrupt Mask on Direct Event input + x+32 + 11 + 1 + + + MR44 + CPU Interrupt Mask on Direct Event input + x+32 + 12 + 1 + + + MR46 + CPU Interrupt Mask on Direct Event input + x+32 + 14 + 1 + + + MR47 + CPU Interrupt Mask on Direct Event input + x+32 + 15 + 1 + + + MR48 + CPU Interrupt Mask on Direct Event input + x+32 + 16 + 1 + + + MR49 + CPU Interrupt Mask on Direct Event input + x+32 + 17 + 1 + + + MR50 + CPU Interrupt Mask on Direct Event input + x+32 + 18 + 1 + + + MR51 + CPU Interrupt Mask on Direct Event input + x+32 + 19 + 1 + + + MR52 + CPU Interrupt Mask on Direct Event input + x+32 + 20 + 1 + + + MR53 + CPU Interrupt Mask on Direct Event input + x+32 + 21 + 1 + + + MR54 + CPU Interrupt Mask on Direct Event input + x+32 + 22 + 1 + + + MR55 + CPU Interrupt Mask on Direct Event input + x+32 + 23 + 1 + + + MR56 + CPU Interrupt Mask on Direct Event input + x+32 + 24 + 1 + + + MR57 + CPU Interrupt Mask on Direct Event input + x+32 + 25 + 1 + + + MR58 + CPU Interrupt Mask on Direct Event input + x+32 + 26 + 1 + + + MR59 + CPU Interrupt Mask on Direct Event input + x+32 + 27 + 1 + + + MR60 + CPU Interrupt Mask on Direct Event input + x+32 + 28 + 1 + + + MR61 + CPU Interrupt Mask on Direct Event input + x+32 + 29 + 1 + + + MR62 + CPU Interrupt Mask on Direct Event input + x+32 + 30 + 1 + + + MR63 + CPU Interrupt Mask on Direct Event input + x+32 + 31 + 1 + + + + + CPUPR2 + CPUPR2 + EXTI pending register + 0x98 + 0x20 + read-only + 0x00000000 + + + PR49 + Configurable event inputs x+32 Pending + bit + 17 + 1 + + + PR51 + Configurable event inputs x+32 Pending + bit + 19 + 1 + + + + + CPUIMR3 + CPUIMR3 + EXTI interrupt mask register + 0xA0 + 0x20 + read-only + 0x00000000 + + + MR64 + CPU Interrupt Mask on Direct Event input + x+64 + 0 + 1 + + + MR65 + CPU Interrupt Mask on Direct Event input + x+64 + 1 + 1 + + + MR66 + CPU Interrupt Mask on Direct Event input + x+64 + 2 + 1 + + + MR67 + CPU Interrupt Mask on Direct Event input + x+64 + 3 + 1 + + + MR68 + CPU Interrupt Mask on Direct Event input + x+64 + 4 + 1 + + + MR69 + CPU Interrupt Mask on Direct Event input + x+64 + 5 + 1 + + + MR70 + CPU Interrupt Mask on Direct Event input + x+64 + 6 + 1 + + + MR71 + CPU Interrupt Mask on Direct Event input + x+64 + 7 + 1 + + + MR72 + CPU Interrupt Mask on Direct Event input + x+64 + 8 + 1 + + + MR73 + CPU Interrupt Mask on Direct Event input + x+64 + 9 + 1 + + + MR74 + CPU Interrupt Mask on Direct Event input + x+64 + 10 + 1 + + + MR75 + CPU Interrupt Mask on Direct Event input + x+64 + 11 + 1 + + + MR76 + CPU Interrupt Mask on Direct Event input + x+64 + 12 + 1 + + + MR77 + CPU Interrupt Mask on Direct Event input + x+64 + 13 + 1 + + + MR78 + CPU Interrupt Mask on Direct Event input + x+64 + 14 + 1 + + + MR79 + CPU Interrupt Mask on Direct Event input + x+64 + 15 + 1 + + + MR80 + CPU Interrupt Mask on Direct Event input + x+64 + 16 + 1 + + + MR82 + CPU Interrupt Mask on Direct Event input + x+64 + 18 + 1 + + + MR84 + CPU Interrupt Mask on Direct Event input + x+64 + 20 + 1 + + + MR85 + CPU Interrupt Mask on Direct Event input + x+64 + 21 + 1 + + + MR86 + CPU Interrupt Mask on Direct Event input + x+64 + 22 + 1 + + + MR87 + CPU Interrupt Mask on Direct Event input + x+64 + 23 + 1 + + + MR88 + CPU Interrupt Mask on Direct Event input + x+64 + 24 + 1 + + + + + CPUEMR3 + CPUEMR3 + EXTI event mask register + 0xA4 + 0x20 + read-only + 0x00000000 + + + MR64 + CPU Event mask on Event input + x+64 + 0 + 1 + + + MR65 + CPU Event mask on Event input + x+64 + 1 + 1 + + + MR66 + CPU Event mask on Event input + x+64 + 2 + 1 + + + MR67 + CPU Event mask on Event input + x+64 + 3 + 1 + + + MR68 + CPU Event mask on Event input + x+64 + 4 + 1 + + + MR69 + CPU Event mask on Event input + x+64 + 5 + 1 + + + MR70 + CPU Event mask on Event input + x+64 + 6 + 1 + + + MR71 + CPU Event mask on Event input + x+64 + 7 + 1 + + + MR72 + CPU Event mask on Event input + x+64 + 8 + 1 + + + MR73 + CPU Event mask on Event input + x+64 + 9 + 1 + + + MR74 + CPU Event mask on Event input + x+64 + 10 + 1 + + + MR75 + CPU Event mask on Event input + x+64 + 11 + 1 + + + MR76 + CPU Event mask on Event input + x+64 + 12 + 1 + + + MR77 + CPU Event mask on Event input + x+64 + 13 + 1 + + + MR78 + CPU Event mask on Event input + x+64 + 14 + 1 + + + MR79 + CPU Event mask on Event input + x+64 + 15 + 1 + + + MR80 + CPU Event mask on Event input + x+64 + 16 + 1 + + + MR82 + CPU Event mask on Event input + x+64 + 18 + 1 + + + MR84 + CPU Event mask on Event input + x+64 + 20 + 1 + + + MR85 + CPU Event mask on Event input + x+64 + 21 + 1 + + + MR86 + CPU Event mask on Event input + x+64 + 22 + 1 + + + MR87 + CPU Event mask on Event input + x+64 + 23 + 1 + + + MR88 + CPU Event mask on Event input + x+64 + 24 + 1 + + + + + CPUPR3 + CPUPR3 + EXTI pending register + 0xA8 + 0x20 + read-only + 0x00000000 + + + PR82 + Configurable event inputs x+64 Pending + bit + 18 + 1 + + + PR84 + Configurable event inputs x+64 Pending + bit + 20 + 1 + + + PR85 + Configurable event inputs x+64 Pending + bit + 21 + 1 + + + PR86 + Configurable event inputs x+64 Pending + bit + 22 + 1 + + + + + + + DELAY_Block_SDMMC1 + DELAY_Block_SDMMC1 + DLYB + 0x52008000 + + 0x0 + 0x1000 + registers + + + WKUP + WKUP1 to WKUP6 pins + 149 + + + + CR + CR + DLYB control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DEN + Delay block enable bit + 0 + 1 + + + SEN + Sampler length enable bit + 1 + 1 + + + + + CFGR + CFGR + DLYB configuration register + 0x4 + 0x20 + read-write + 0x00000000 + + + SEL + Select the phase for the Output + clock + 0 + 4 + + + UNIT + Delay Defines the delay of a Unit delay + cell + 8 + 7 + + + LNG + Delay line length value + 16 + 12 + + + LNGF + Length valid flag + 31 + 1 + + + + + + + DELAY_Block_QUADSPI + 0x52006000 + + + DELAY_Block_SDMMC2 + 0x48022800 + + + Flash + Flash + Flash + 0x52002000 + + 0x0 + 0x1000 + registers + + + FLASH + Flash memory + 4 + + + + ACR + ACR + Access control register + 0x0 + 0x20 + read-write + 0x00000600 + + + LATENCY + Read latency + 0 + 3 + + + WRHIGHFREQ + Flash signal delay + 4 + 2 + + + + + ACR_ + ACR_ + Access control register + 0x100 + 0x20 + read-write + 0x00000000 + + + LATENCY + Read latency + 0 + 3 + + + WRHIGHFREQ + Flash signal delay + 4 + 2 + + + + + KEYR1 + KEYR1 + FLASH key register for bank 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + KEYR1 + Bank 1 access configuration unlock + key + 0 + 32 + + + + + OPTKEYR + OPTKEYR + FLASH option key register + 0x8 + 0x20 + read-write + 0x00000000 + + + OPTKEYR + Unlock key option bytes + 0 + 32 + + + + + OPTKEYR_ + OPTKEYR_ + FLASH option key register + 0x108 + 0x20 + read-write + 0x00000000 + + + OPTKEYR + Unlock key option bytes + 0 + 32 + + + + + CR1 + CR1 + FLASH control register for bank + 1 + 0xC + 0x20 + read-write + 0x00000000 + + + LOCK1 + Bank 1 configuration lock + bit + 0 + 1 + + + PG1 + Bank 1 program enable bit + 1 + 1 + + + SER1 + Bank 1 sector erase + request + 2 + 1 + + + BER1 + Bank 1 erase request + 3 + 1 + + + PSIZE1 + Bank 1 program size + 4 + 2 + + + FW1 + Bank 1 write forcing control + bit + 6 + 1 + + + START1 + Bank 1 bank or sector erase start + control bit + 7 + 1 + + + SNB1 + Bank 1 sector erase selection + number + 8 + 3 + + + CRC_EN + Bank 1 CRC control bit + 15 + 1 + + + EOPIE1 + Bank 1 end-of-program interrupt control + bit + 16 + 1 + + + WRPERRIE1 + Bank 1 write protection error interrupt + enable bit + 17 + 1 + + + PGSERRIE1 + Bank 1 programming sequence error + interrupt enable bit + 18 + 1 + + + STRBERRIE1 + Bank 1 strobe error interrupt enable + bit + 19 + 1 + + + INCERRIE1 + Bank 1 inconsistency error interrupt + enable bit + 21 + 1 + + + OPERRIE1 + Bank 1 write/erase error interrupt + enable bit + 22 + 1 + + + RDPERRIE1 + Bank 1 read protection error interrupt + enable bit + 23 + 1 + + + RDSERRIE1 + Bank 1 secure error interrupt enable + bit + 24 + 1 + + + SNECCERRIE1 + Bank 1 ECC single correction error + interrupt enable bit + 25 + 1 + + + DBECCERRIE1 + Bank 1 ECC double detection error + interrupt enable bit + 26 + 1 + + + CRCENDIE1 + Bank 1 end of CRC calculation interrupt + enable bit + 27 + 1 + + + + + SR1 + SR1 + FLASH status register for bank + 1 + 0x10 + 0x20 + read-write + 0x00000000 + + + BSY1 + Bank 1 ongoing program + flag + 0 + 1 + + + WBNE1 + Bank 1 write buffer not empty + flag + 1 + 1 + + + QW1 + Bank 1 wait queue flag + 2 + 1 + + + CRC_BUSY1 + Bank 1 CRC busy flag + 3 + 1 + + + EOP1 + Bank 1 end-of-program flag + 16 + 1 + + + WRPERR1 + Bank 1 write protection error + flag + 17 + 1 + + + PGSERR1 + Bank 1 programming sequence error + flag + 18 + 1 + + + STRBERR1 + Bank 1 strobe error flag + 19 + 1 + + + INCERR1 + Bank 1 inconsistency error + flag + 21 + 1 + + + OPERR1 + Bank 1 write/erase error + flag + 22 + 1 + + + RDPERR1 + Bank 1 read protection error + flag + 23 + 1 + + + RDSERR1 + Bank 1 secure error flag + 24 + 1 + + + SNECCERR11 + Bank 1 single correction error + flag + 25 + 1 + + + DBECCERR1 + Bank 1 ECC double detection error + flag + 26 + 1 + + + CRCEND1 + Bank 1 CRC-complete flag + 27 + 1 + + + + + CCR1 + CCR1 + FLASH clear control register for bank + 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + CLR_EOP1 + Bank 1 EOP1 flag clear bit + 16 + 1 + + + CLR_WRPERR1 + Bank 1 WRPERR1 flag clear + bit + 17 + 1 + + + CLR_PGSERR1 + Bank 1 PGSERR1 flag clear + bi + 18 + 1 + + + CLR_STRBERR1 + Bank 1 STRBERR1 flag clear + bit + 19 + 1 + + + CLR_INCERR1 + Bank 1 INCERR1 flag clear + bit + 21 + 1 + + + CLR_OPERR1 + Bank 1 OPERR1 flag clear + bit + 22 + 1 + + + CLR_RDPERR1 + Bank 1 RDPERR1 flag clear + bit + 23 + 1 + + + CLR_RDSERR1 + Bank 1 RDSERR1 flag clear + bit + 24 + 1 + + + CLR_SNECCERR1 + Bank 1 SNECCERR1 flag clear + bit + 25 + 1 + + + CLR_DBECCERR1 + Bank 1 DBECCERR1 flag clear + bit + 26 + 1 + + + CLR_CRCEND1 + Bank 1 CRCEND1 flag clear + bit + 27 + 1 + + + + + OPTCR + OPTCR + FLASH option control register + 0x18 + 0x20 + read-write + 0x00000000 + + + OPTLOCK + FLASH_OPTCR lock option configuration + bit + 0 + 1 + + + OPTSTART + Option byte start change option + configuration bit + 1 + 1 + + + MER + Flash mass erase enable + bit + 4 + 1 + + + OPTCHANGEERRIE + Option byte change error interrupt + enable bit + 30 + 1 + + + SWAP_BANK + Bank swapping configuration + bit + 31 + 1 + + + + + OPTCR_ + OPTCR_ + FLASH option control register + 0x118 + 0x20 + read-write + 0x00000000 + + + OPTLOCK + FLASH_OPTCR lock option configuration + bit + 0 + 1 + + + OPTSTART + Option byte start change option + configuration bit + 1 + 1 + + + MER + Flash mass erase enable + bit + 4 + 1 + + + OPTCHANGEERRIE + Option byte change error interrupt + enable bit + 30 + 1 + + + SWAP_BANK + Bank swapping configuration + bit + 31 + 1 + + + + + OPTSR_CUR_ + OPTSR_CUR_ + FLASH option status register + 0x11C + 0x20 + read-write + 0x00000000 + + + OPT_BUSY + Option byte change ongoing + flag + 0 + 1 + + + BOR_LEV + Brownout level option status + bit + 2 + 2 + + + IWDG1_HW + IWDG1 control option status + bit + 4 + 1 + + + nRST_STOP_D1 + D1 DStop entry reset option status + bit + 6 + 1 + + + nRST_STBY_D1 + D1 DStandby entry reset option status + bit + 7 + 1 + + + RDP + Readout protection level option status + byte + 8 + 8 + + + FZ_IWDG_STOP + IWDG Stop mode freeze option status + bit + 17 + 1 + + + FZ_IWDG_SDBY + IWDG Standby mode freeze option status + bit + 18 + 1 + + + ST_RAM_SIZE + DTCM RAM size option + status + 19 + 2 + + + SECURITY + Security enable option status + bit + 21 + 1 + + + RSS1 + User option bit 1 + 26 + 1 + + + PERSO_OK + Device personalization status + bit + 28 + 1 + + + IO_HSLV + I/O high-speed at low-voltage status bit + (PRODUCT_BELOW_25V) + 29 + 1 + + + OPTCHANGEERR + Option byte change error + flag + 30 + 1 + + + SWAP_BANK_OPT + Bank swapping option status + bit + 31 + 1 + + + + + OPTSR_CUR + OPTSR_CUR + FLASH option status register + 0x1C + 0x20 + read-write + 0x00000000 + + + OPT_BUSY + Option byte change ongoing + flag + 0 + 1 + + + BOR_LEV + Brownout level option status + bit + 2 + 2 + + + IWDG1_HW + IWDG1 control option status + bit + 4 + 1 + + + nRST_STOP_D1 + D1 DStop entry reset option status + bit + 6 + 1 + + + nRST_STBY_D1 + D1 DStandby entry reset option status + bit + 7 + 1 + + + RDP + Readout protection level option status + byte + 8 + 8 + + + FZ_IWDG_STOP + IWDG Stop mode freeze option status + bit + 17 + 1 + + + FZ_IWDG_SDBY + IWDG Standby mode freeze option status + bit + 18 + 1 + + + ST_RAM_SIZE + DTCM RAM size option + status + 19 + 2 + + + SECURITY + Security enable option status + bit + 21 + 1 + + + RSS1 + User option bit 1 + 26 + 1 + + + PERSO_OK + Device personalization status + bit + 28 + 1 + + + IO_HSLV + I/O high-speed at low-voltage status bit + (PRODUCT_BELOW_25V) + 29 + 1 + + + OPTCHANGEERR + Option byte change error + flag + 30 + 1 + + + SWAP_BANK_OPT + Bank swapping option status + bit + 31 + 1 + + + + + OPTSR_PRG + OPTSR_PRG + FLASH option status register + 0x20 + 0x20 + read-write + 0x00000000 + + + BOR_LEV + BOR reset level option configuration + bits + 2 + 2 + + + IWDG1_HW + IWDG1 option configuration + bit + 4 + 1 + + + nRST_STOP_D1 + Option byte erase after D1 DStop option + configuration bit + 6 + 1 + + + nRST_STBY_D1 + Option byte erase after D1 DStandby + option configuration bit + 7 + 1 + + + RDP + Readout protection level option + configuration byte + 8 + 8 + + + FZ_IWDG_STOP + IWDG Stop mode freeze option + configuration bit + 17 + 1 + + + FZ_IWDG_SDBY + IWDG Standby mode freeze option + configuration bit + 18 + 1 + + + ST_RAM_SIZE + DTCM size select option configuration + bits + 19 + 2 + + + SECURITY + Security option configuration + bit + 21 + 1 + + + RSS1 + User option configuration bit + 1 + 26 + 1 + + + RSS2 + User option configuration bit + 2 + 27 + 1 + + + IO_HSLV + I/O high-speed at low-voltage + (PRODUCT_BELOW_25V) + 29 + 1 + + + SWAP_BANK_OPT + Bank swapping option configuration + bit + 31 + 1 + + + + + OPTSR_PRG_ + OPTSR_PRG_ + FLASH option status register + 0x120 + 0x20 + read-write + 0x00000000 + + + BOR_LEV + BOR reset level option configuration + bits + 2 + 2 + + + IWDG1_HW + IWDG1 option configuration + bit + 4 + 1 + + + nRST_STOP_D1 + Option byte erase after D1 DStop option + configuration bit + 6 + 1 + + + nRST_STBY_D1 + Option byte erase after D1 DStandby + option configuration bit + 7 + 1 + + + RDP + Readout protection level option + configuration byte + 8 + 8 + + + FZ_IWDG_STOP + IWDG Stop mode freeze option + configuration bit + 17 + 1 + + + FZ_IWDG_SDBY + IWDG Standby mode freeze option + configuration bit + 18 + 1 + + + ST_RAM_SIZE + DTCM size select option configuration + bits + 19 + 2 + + + SECURITY + Security option configuration + bit + 21 + 1 + + + RSS1 + User option configuration bit + 1 + 26 + 1 + + + RSS2 + User option configuration bit + 2 + 27 + 1 + + + IO_HSLV + I/O high-speed at low-voltage + (PRODUCT_BELOW_25V) + 29 + 1 + + + SWAP_BANK_OPT + Bank swapping option configuration + bit + 31 + 1 + + + + + OPTCCR_ + OPTCCR_ + FLASH option clear control + register + 0x124 + 0x20 + write-only + 0x00000000 + + + CLR_OPTCHANGEERR + OPTCHANGEERR reset bit + 30 + 1 + + + + + OPTCCR + OPTCCR + FLASH option clear control + register + 0x24 + 0x20 + write-only + 0x00000000 + + + CLR_OPTCHANGEERR + OPTCHANGEERR reset bit + 30 + 1 + + + + + PRAR_CUR1 + PRAR_CUR1 + FLASH protection address for bank + 1 + 0x28 + 0x20 + read-only + 0x00000000 + + + PROT_AREA_START1 + Bank 1 lowest PCROP protected + address + 0 + 12 + + + PROT_AREA_END1 + Bank 1 highest PCROP protected + address + 16 + 12 + + + DMEP1 + Bank 1 PCROP protected erase enable + option status bit + 31 + 1 + + + + + PRAR_PRG1 + PRAR_PRG1 + FLASH protection address for bank + 1 + 0x2C + 0x20 + read-write + 0x00000000 + + + PROT_AREA_START1 + Bank 1 lowest PCROP protected address + configuration + 0 + 12 + + + PROT_AREA_END1 + Bank 1 highest PCROP protected address + configuration + 16 + 12 + + + DMEP1 + Bank 1 PCROP protected erase enable + option configuration bit + 31 + 1 + + + + + SCAR_CUR1 + SCAR_CUR1 + FLASH secure address for bank + 1 + 0x30 + 0x20 + read-write + 0x00000000 + + + SEC_AREA_START1 + Bank 1 lowest secure protected + address + 0 + 12 + + + SEC_AREA_END1 + Bank 1 highest secure protected + address + 16 + 12 + + + DMES1 + Bank 1 secure protected erase enable + option status bit + 31 + 1 + + + + + SCAR_PRG1 + SCAR_PRG1 + FLASH secure address for bank + 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + SEC_AREA_START1 + Bank 1 lowest secure protected address + configuration + 0 + 12 + + + SEC_AREA_END1 + Bank 1 highest secure protected address + configuration + 16 + 12 + + + DMES1 + Bank 1 secure protected erase enable + option configuration bit + 31 + 1 + + + + + WPSN_CUR1R + WPSN_CUR1R + FLASH write sector protection for bank + 1 + 0x38 + 0x20 + read-only + 0x00000000 + + + WRPSn1 + Bank 1 sector write protection option + status byte + 0 + 8 + + + + + WPSN_PRG1R + WPSN_PRG1R + FLASH write sector protection for bank + 1 + 0x3C + 0x20 + read-write + 0x00000000 + + + WRPSn1 + Bank 1 sector write protection + configuration byte + 0 + 8 + + + + + BOOT_CURR + BOOT_CURR + FLASH register with boot + address + 0x40 + 0x20 + read-only + 0x00000000 + + + BOOT_ADD0 + Boot address 0 + 0 + 16 + + + BOOT_ADD1 + Boot address 1 + 16 + 16 + + + + + BOOT_PRGR + BOOT_PRGR + FLASH register with boot + address + 0x44 + 0x20 + read-only + 0x00000000 + + + BOOT_ADD0 + Boot address 0 + 0 + 16 + + + BOOT_ADD1 + Boot address 1 + 16 + 16 + + + + + CRCCR1 + CRCCR1 + FLASH CRC control register for bank + 1 + 0x50 + 0x20 + read-write + 0x00000000 + + + CRC_SECT + Bank 1 CRC sector number + 0 + 3 + + + ALL_BANK + Bank 1 CRC select bit + 7 + 1 + + + CRC_BY_SECT + Bank 1 CRC sector mode select + bit + 8 + 1 + + + ADD_SECT + Bank 1 CRC sector select + bit + 9 + 1 + + + CLEAN_SECT + Bank 1 CRC sector list clear + bit + 10 + 1 + + + START_CRC + Bank 1 CRC start bit + 16 + 1 + + + CLEAN_CRC + Bank 1 CRC clear bit + 17 + 1 + + + CRC_BURST + Bank 1 CRC burst size + 20 + 2 + + + + + CRCSADD1R + CRCSADD1R + FLASH CRC start address register for bank + 1 + 0x54 + 0x20 + read-write + 0x00000000 + + + CRC_START_ADDR + CRC start address on bank + 1 + 0 + 32 + + + + + CRCEADD1R + CRCEADD1R + FLASH CRC end address register for bank + 1 + 0x58 + 0x20 + read-write + 0x00000000 + + + CRC_END_ADDR + CRC end address on bank 1 + 0 + 32 + + + + + CRCDATAR + CRCDATAR + FLASH CRC data register + 0x5C + 0x20 + read-write + 0x00000000 + + + CRC_DATA + CRC result + 0 + 32 + + + + + ECC_FA1R + ECC_FA1R + FLASH ECC fail address for bank + 1 + 0x60 + 0x20 + read-only + 0x00000000 + + + FAIL_ECC_ADDR1 + Bank 1 ECC error address + 0 + 15 + + + + + KEYR2 + KEYR2 + FLASH key register for bank 2 + 0x104 + 0x20 + read-only + 0x00000000 + + + KEYR2 + Bank 2 access configuration unlock + key + 0 + 32 + + + + + CR2 + CR2 + FLASH control register for bank + 2 + 0x10C + 0x20 + read-write + 0x00000000 + + + LOCK2 + Bank 2 configuration lock + bit + 0 + 1 + + + PG2 + Bank 2 program enable bit + 1 + 1 + + + SER2 + Bank 2 sector erase + request + 2 + 1 + + + BER2 + Bank 2 erase request + 3 + 1 + + + PSIZE2 + Bank 2 program size + 4 + 2 + + + FW2 + Bank 2 write forcing control + bit + 6 + 1 + + + START2 + Bank 2 bank or sector erase start + control bit + 7 + 1 + + + SNB2 + Bank 2 sector erase selection + number + 8 + 3 + + + CRC_EN + Bank 2 CRC control bit + 15 + 1 + + + EOPIE2 + Bank 2 end-of-program interrupt control + bit + 16 + 1 + + + WRPERRIE2 + Bank 2 write protection error interrupt + enable bit + 17 + 1 + + + PGSERRIE2 + Bank 2 programming sequence error + interrupt enable bit + 18 + 1 + + + STRBERRIE2 + Bank 2 strobe error interrupt enable + bit + 19 + 1 + + + INCERRIE2 + Bank 2 inconsistency error interrupt + enable bit + 21 + 1 + + + OPERRIE2 + Bank 2 write/erase error interrupt + enable bit + 22 + 1 + + + RDPERRIE2 + Bank 2 read protection error interrupt + enable bit + 23 + 1 + + + RDSERRIE2 + Bank 2 secure error interrupt enable + bit + 24 + 1 + + + SNECCERRIE2 + Bank 2 ECC single correction error + interrupt enable bit + 25 + 1 + + + DBECCERRIE2 + Bank 2 ECC double detection error + interrupt enable bit + 26 + 1 + + + CRCENDIE2 + Bank 2 end of CRC calculation interrupt + enable bit + 27 + 1 + + + + + SR2 + SR2 + FLASH status register for bank + 2 + 0x110 + 0x20 + read-write + 0x00000000 + + + BSY2 + Bank 2 ongoing program + flag + 0 + 1 + + + WBNE2 + Bank 2 write buffer not empty + flag + 1 + 1 + + + QW2 + Bank 2 wait queue flag + 2 + 1 + + + CRC_BUSY2 + Bank 2 CRC busy flag + 3 + 1 + + + EOP2 + Bank 2 end-of-program flag + 16 + 1 + + + WRPERR2 + Bank 2 write protection error + flag + 17 + 1 + + + PGSERR2 + Bank 2 programming sequence error + flag + 18 + 1 + + + STRBERR2 + Bank 2 strobe error flag + 19 + 1 + + + INCERR2 + Bank 2 inconsistency error + flag + 21 + 1 + + + OPERR2 + Bank 2 write/erase error + flag + 22 + 1 + + + RDPERR2 + Bank 2 read protection error + flag + 23 + 1 + + + RDSERR2 + Bank 2 secure error flag + 24 + 1 + + + SNECCERR2 + Bank 2 single correction error + flag + 25 + 1 + + + DBECCERR2 + Bank 2 ECC double detection error + flag + 26 + 1 + + + CRCEND2 + Bank 2 CRC-complete flag + 27 + 1 + + + + + CCR2 + CCR2 + FLASH clear control register for bank + 2 + 0x114 + 0x20 + read-write + 0x00000000 + + + CLR_EOP2 + Bank 1 EOP1 flag clear bit + 16 + 1 + + + CLR_WRPERR2 + Bank 2 WRPERR1 flag clear + bit + 17 + 1 + + + CLR_PGSERR2 + Bank 2 PGSERR1 flag clear + bi + 18 + 1 + + + CLR_STRBERR2 + Bank 2 STRBERR1 flag clear + bit + 19 + 1 + + + CLR_INCERR2 + Bank 2 INCERR1 flag clear + bit + 21 + 1 + + + CLR_OPERR2 + Bank 2 OPERR1 flag clear + bit + 22 + 1 + + + CLR_RDPERR2 + Bank 2 RDPERR1 flag clear + bit + 23 + 1 + + + CLR_RDSERR1 + Bank 1 RDSERR1 flag clear + bit + 24 + 1 + + + CLR_SNECCERR2 + Bank 2 SNECCERR1 flag clear + bit + 25 + 1 + + + CLR_DBECCERR1 + Bank 1 DBECCERR1 flag clear + bit + 26 + 1 + + + CLR_CRCEND2 + Bank 2 CRCEND1 flag clear + bit + 27 + 1 + + + + + PRAR_CUR2 + PRAR_CUR2 + FLASH protection address for bank + 1 + 0x128 + 0x20 + read-only + 0x00000000 + + + PROT_AREA_START2 + Bank 2 lowest PCROP protected + address + 0 + 12 + + + PROT_AREA_END2 + Bank 2 highest PCROP protected + address + 16 + 12 + + + DMEP2 + Bank 2 PCROP protected erase enable + option status bit + 31 + 1 + + + + + PRAR_PRG2 + PRAR_PRG2 + FLASH protection address for bank + 2 + PRAR_PRG1 + 0x2C + 0x20 + read-write + 0x00000000 + + + PROT_AREA_START2 + Bank 2 lowest PCROP protected address + configuration + 0 + 12 + + + PROT_AREA_END2 + Bank 2 highest PCROP protected address + configuration + 16 + 12 + + + DMEP2 + Bank 2 PCROP protected erase enable + option configuration bit + 31 + 1 + + + + + SCAR_CUR2 + SCAR_CUR2 + FLASH secure address for bank + 2 + 0x130 + 0x20 + read-write + 0x00000000 + + + SEC_AREA_START2 + Bank 2 lowest secure protected + address + 0 + 12 + + + SEC_AREA_END2 + Bank 2 highest secure protected + address + 16 + 12 + + + DMES2 + Bank 2 secure protected erase enable + option status bit + 31 + 1 + + + + + SCAR_PRG2 + SCAR_PRG2 + FLASH secure address for bank + 2 + 0x134 + 0x20 + read-write + 0x00000000 + + + SEC_AREA_START2 + Bank 2 lowest secure protected address + configuration + 0 + 12 + + + SEC_AREA_END2 + Bank 2 highest secure protected address + configuration + 16 + 12 + + + DMES2 + Bank 2 secure protected erase enable + option configuration bit + 31 + 1 + + + + + WPSN_CUR2R + WPSN_CUR2R + FLASH write sector protection for bank + 2 + 0x138 + 0x20 + read-only + 0x00000000 + + + WRPSn2 + Bank 2 sector write protection option + status byte + 0 + 8 + + + + + WPSN_PRG2R + WPSN_PRG2R + FLASH write sector protection for bank + 2 + 0x13C + 0x20 + read-write + 0x00000000 + + + WRPSn2 + Bank 2 sector write protection + configuration byte + 0 + 8 + + + + + CRCCR2 + CRCCR2 + FLASH CRC control register for bank + 1 + 0x150 + 0x20 + read-write + 0x00000000 + + + CRC_SECT + Bank 2 CRC sector number + 0 + 3 + + + ALL_BANK + Bank 2 CRC select bit + 7 + 1 + + + CRC_BY_SECT + Bank 2 CRC sector mode select + bit + 8 + 1 + + + ADD_SECT + Bank 2 CRC sector select + bit + 9 + 1 + + + CLEAN_SECT + Bank 2 CRC sector list clear + bit + 10 + 1 + + + START_CRC + Bank 2 CRC start bit + 16 + 1 + + + CLEAN_CRC + Bank 2 CRC clear bit + 17 + 1 + + + CRC_BURST + Bank 2 CRC burst size + 20 + 2 + + + + + CRCSADD2R + CRCSADD2R + FLASH CRC start address register for bank + 2 + 0x154 + 0x20 + read-write + 0x00000000 + + + CRC_START_ADDR + CRC start address on bank + 2 + 0 + 32 + + + + + CRCEADD2R + CRCEADD2R + FLASH CRC end address register for bank + 2 + 0x158 + 0x20 + read-write + 0x00000000 + + + CRC_END_ADDR + CRC end address on bank 2 + 0 + 32 + + + + + ECC_FA2R + ECC_FA2R + FLASH ECC fail address for bank + 2 + 0x160 + 0x20 + read-only + 0x00000000 + + + FAIL_ECC_ADDR2 + Bank 2 ECC error address + 0 + 15 + + + + + + + AXI + AXI interconnect registers + AXI + 0x51000000 + + 0x0 + 0x100000 + registers + + + + AXI_PERIPH_ID_4 + AXI_PERIPH_ID_4 + AXI interconnect - peripheral ID4 + register + 0x1FD0 + 0x20 + read-only + 0x00000004 + + + JEP106CON + JEP106 continuation code + 0 + 4 + + + KCOUNT4 + Register file size + 4 + 4 + + + + + AXI_PERIPH_ID_0 + AXI_PERIPH_ID_0 + AXI interconnect - peripheral ID0 + register + 0x1FE0 + 0x20 + read-only + 0x00000004 + + + PARTNUM + Peripheral part number bits 0 to + 7 + 0 + 8 + + + + + AXI_PERIPH_ID_1 + AXI_PERIPH_ID_1 + AXI interconnect - peripheral ID1 + register + 0x1FE4 + 0x20 + read-only + 0x00000004 + + + PARTNUM + Peripheral part number bits 8 to + 11 + 0 + 4 + + + JEP106I + JEP106 identity bits 0 to + 3 + 4 + 4 + + + + + AXI_PERIPH_ID_2 + AXI_PERIPH_ID_2 + AXI interconnect - peripheral ID2 + register + 0x1FE8 + 0x20 + read-only + 0x00000004 + + + JEP106ID + JEP106 Identity bits 4 to + 6 + 0 + 3 + + + JEDEC + JEP106 code flag + 3 + 1 + + + REVISION + Peripheral revision number + 4 + 4 + + + + + AXI_PERIPH_ID_3 + AXI_PERIPH_ID_3 + AXI interconnect - peripheral ID3 + register + 0x1FEC + 0x20 + read-only + 0x00000004 + + + CUST_MOD_NUM + Customer modification + 0 + 4 + + + REV_AND + Customer version + 4 + 4 + + + + + AXI_COMP_ID_0 + AXI_COMP_ID_0 + AXI interconnect - component ID0 + register + 0x1FF0 + 0x20 + read-only + 0x00000004 + + + PREAMBLE + Preamble bits 0 to 7 + 0 + 8 + + + + + AXI_COMP_ID_1 + AXI_COMP_ID_1 + AXI interconnect - component ID1 + register + 0x1FF4 + 0x20 + read-only + 0x00000004 + + + PREAMBLE + Preamble bits 8 to 11 + 0 + 4 + + + CLASS + Component class + 4 + 4 + + + + + AXI_COMP_ID_2 + AXI_COMP_ID_2 + AXI interconnect - component ID2 + register + 0x1FF8 + 0x20 + read-only + 0x00000004 + + + PREAMBLE + Preamble bits 12 to 19 + 0 + 8 + + + + + AXI_COMP_ID_3 + AXI_COMP_ID_3 + AXI interconnect - component ID3 + register + 0x1FFC + 0x20 + read-only + 0x00000004 + + + PREAMBLE + Preamble bits 20 to 27 + 0 + 8 + + + + + AXI_TARG1_FN_MOD_ISS_BM + AXI_TARG1_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x2008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG2_FN_MOD_ISS_BM + AXI_TARG2_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x3008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG3_FN_MOD_ISS_BM + AXI_TARG3_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x4008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG4_FN_MOD_ISS_BM + AXI_TARG4_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x5008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG5_FN_MOD_ISS_BM + AXI_TARG5_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x6008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG6_FN_MOD_ISS_BM + AXI_TARG6_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x7008 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG7_FN_MOD_ISS_BM + AXI_TARG7_FN_MOD_ISS_BM + AXI interconnect - TARG x bus matrix issuing + functionality register + 0x800C + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + READ_ISS_OVERRIDE + 0 + 1 + + + WRITE_ISS_OVERRIDE + Switch matrix write issuing override for + target + 1 + 1 + + + + + AXI_TARG1_FN_MOD2 + AXI_TARG1_FN_MOD2 + AXI interconnect - TARG x bus matrix + functionality 2 register + 0x2024 + 0x20 + read-write + 0x00000004 + + + BYPASS_MERGE + Disable packing of beats to match the + output data width + 0 + 1 + + + + + AXI_TARG2_FN_MOD2 + AXI_TARG2_FN_MOD2 + AXI interconnect - TARG x bus matrix + functionality 2 register + 0x3024 + 0x20 + read-write + 0x00000004 + + + BYPASS_MERGE + Disable packing of beats to match the + output data width + 0 + 1 + + + + + AXI_TARG7_FN_MOD2 + AXI_TARG7_FN_MOD2 + AXI interconnect - TARG x bus matrix + functionality 2 register + 0x8024 + 0x20 + read-write + 0x00000004 + + + BYPASS_MERGE + Disable packing of beats to match the + output data width + 0 + 1 + + + + + AXI_TARG1_FN_MOD_LB + AXI_TARG1_FN_MOD_LB + AXI interconnect - TARG x long burst + functionality modification + 0x202C + 0x20 + read-write + 0x00000004 + + + FN_MOD_LB + Controls burst breaking of long + bursts + 0 + 1 + + + + + AXI_TARG2_FN_MOD_LB + AXI_TARG2_FN_MOD_LB + AXI interconnect - TARG x long burst + functionality modification + 0x302C + 0x20 + read-write + 0x00000004 + + + FN_MOD_LB + Controls burst breaking of long + bursts + 0 + 1 + + + + + AXI_TARG1_FN_MOD + AXI_TARG1_FN_MOD + AXI interconnect - TARG x long burst + functionality modification + 0x2108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override AMIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override AMIB write issuing + capability + 1 + 1 + + + + + AXI_TARG2_FN_MOD + AXI_TARG2_FN_MOD + AXI interconnect - TARG x long burst + functionality modification + 0x3108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override AMIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override AMIB write issuing + capability + 1 + 1 + + + + + AXI_TARG7_FN_MOD + AXI_TARG7_FN_MOD + AXI interconnect - TARG x long burst + functionality modification + 0x8108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override AMIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override AMIB write issuing + capability + 1 + 1 + + + + + AXI_INI1_FN_MOD2 + AXI_INI1_FN_MOD2 + AXI interconnect - INI x functionality + modification 2 register + 0x42024 + 0x20 + read-write + 0x00000004 + + + BYPASS_MERGE + Disables alteration of transactions by + the up-sizer unless required by the + protocol + 0 + 1 + + + + + AXI_INI3_FN_MOD2 + AXI_INI3_FN_MOD2 + AXI interconnect - INI x functionality + modification 2 register + 0x44024 + 0x20 + read-write + 0x00000004 + + + BYPASS_MERGE + Disables alteration of transactions by + the up-sizer unless required by the + protocol + 0 + 1 + + + + + AXI_INI1_FN_MOD_AHB + AXI_INI1_FN_MOD_AHB + AXI interconnect - INI x AHB functionality + modification register + 0x42028 + 0x20 + read-write + 0x00000004 + + + RD_INC_OVERRIDE + Converts all AHB-Lite write transactions + to a series of single beat AXI + 0 + 1 + + + WR_INC_OVERRIDE + Converts all AHB-Lite read transactions + to a series of single beat AXI + 1 + 1 + + + + + AXI_INI3_FN_MOD_AHB + AXI_INI3_FN_MOD_AHB + AXI interconnect - INI x AHB functionality + modification register + 0x44028 + 0x20 + read-write + 0x00000004 + + + RD_INC_OVERRIDE + Converts all AHB-Lite write transactions + to a series of single beat AXI + 0 + 1 + + + WR_INC_OVERRIDE + Converts all AHB-Lite read transactions + to a series of single beat AXI + 1 + 1 + + + + + AXI_INI1_READ_QOS + AXI_INI1_READ_QOS + AXI interconnect - INI x read QoS + register + 0x42100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI2_READ_QOS + AXI_INI2_READ_QOS + AXI interconnect - INI x read QoS + register + 0x43100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI3_READ_QOS + AXI_INI3_READ_QOS + AXI interconnect - INI x read QoS + register + 0x44100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI4_READ_QOS + AXI_INI4_READ_QOS + AXI interconnect - INI x read QoS + register + 0x45100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI5_READ_QOS + AXI_INI5_READ_QOS + AXI interconnect - INI x read QoS + register + 0x46100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI6_READ_QOS + AXI_INI6_READ_QOS + AXI interconnect - INI x read QoS + register + 0x47100 + 0x20 + read-write + 0x00000004 + + + AR_QOS + Read channel QoS setting + 0 + 4 + + + + + AXI_INI1_WRITE_QOS + AXI_INI1_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x42104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI2_WRITE_QOS + AXI_INI2_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x43104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI3_WRITE_QOS + AXI_INI3_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x44104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI4_WRITE_QOS + AXI_INI4_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x45104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI5_WRITE_QOS + AXI_INI5_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x46104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI6_WRITE_QOS + AXI_INI6_WRITE_QOS + AXI interconnect - INI x write QoS + register + 0x47104 + 0x20 + read-write + 0x00000004 + + + AW_QOS + Write channel QoS setting + 0 + 4 + + + + + AXI_INI1_FN_MOD + AXI_INI1_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x42108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + AXI_INI2_FN_MOD + AXI_INI2_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x43108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + AXI_INI3_FN_MOD + AXI_INI3_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x44108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + AXI_INI4_FN_MOD + AXI_INI4_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x45108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + AXI_INI5_FN_MOD + AXI_INI5_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x46108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + AXI_INI6_FN_MOD + AXI_INI6_FN_MOD + AXI interconnect - INI x issuing + functionality modification register + 0x47108 + 0x20 + read-write + 0x00000004 + + + READ_ISS_OVERRIDE + Override ASIB read issuing + capability + 0 + 1 + + + WRITE_ISS_OVERRIDE + Override ASIB write issuing + capability + 1 + 1 + + + + + + + + + DCMI + Digital camera interface + DCMI + 0x48020000 + + 0x0 + 0x400 + registers + + + DCMI + DCMI global interrupt + 78 + + + + CR + CR + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + OELS + Odd/Even Line Select (Line Select + Start) + 20 + 1 + + + LSM + Line Select mode + 19 + 1 + + + OEBS + Odd/Even Byte Select (Byte Select + Start) + 18 + 1 + + + BSM + Byte Select mode + 16 + 2 + + + ENABLE + DCMI enable + 14 + 1 + + + EDM + Extended data mode + 10 + 2 + + + FCRC + Frame capture rate control + 8 + 2 + + + VSPOL + Vertical synchronization + polarity + 7 + 1 + + + HSPOL + Horizontal synchronization + polarity + 6 + 1 + + + PCKPOL + Pixel clock polarity + 5 + 1 + + + ESS + Embedded synchronization + select + 4 + 1 + + + JPEG + JPEG format + 3 + 1 + + + CROP + Crop feature + 2 + 1 + + + CM + Capture mode + 1 + 1 + + + CAPTURE + Capture enable + 0 + 1 + + + + + SR + SR + status register + 0x4 + 0x20 + read-only + 0x0000 + + + FNE + FIFO not empty + 2 + 1 + + + VSYNC + VSYNC + 1 + 1 + + + HSYNC + HSYNC + 0 + 1 + + + + + RIS + RIS + raw interrupt status register + 0x8 + 0x20 + read-only + 0x0000 + + + LINE_RIS + Line raw interrupt status + 4 + 1 + + + VSYNC_RIS + VSYNC raw interrupt status + 3 + 1 + + + ERR_RIS + Synchronization error raw interrupt + status + 2 + 1 + + + OVR_RIS + Overrun raw interrupt + status + 1 + 1 + + + FRAME_RIS + Capture complete raw interrupt + status + 0 + 1 + + + + + IER + IER + interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + LINE_IE + Line interrupt enable + 4 + 1 + + + VSYNC_IE + VSYNC interrupt enable + 3 + 1 + + + ERR_IE + Synchronization error interrupt + enable + 2 + 1 + + + OVR_IE + Overrun interrupt enable + 1 + 1 + + + FRAME_IE + Capture complete interrupt + enable + 0 + 1 + + + + + MIS + MIS + masked interrupt status + register + 0x10 + 0x20 + read-only + 0x0000 + + + LINE_MIS + Line masked interrupt + status + 4 + 1 + + + VSYNC_MIS + VSYNC masked interrupt + status + 3 + 1 + + + ERR_MIS + Synchronization error masked interrupt + status + 2 + 1 + + + OVR_MIS + Overrun masked interrupt + status + 1 + 1 + + + FRAME_MIS + Capture complete masked interrupt + status + 0 + 1 + + + + + ICR + ICR + interrupt clear register + 0x14 + 0x20 + write-only + 0x0000 + + + LINE_ISC + line interrupt status + clear + 4 + 1 + + + VSYNC_ISC + Vertical synch interrupt status + clear + 3 + 1 + + + ERR_ISC + Synchronization error interrupt status + clear + 2 + 1 + + + OVR_ISC + Overrun interrupt status + clear + 1 + 1 + + + FRAME_ISC + Capture complete interrupt status + clear + 0 + 1 + + + + + ESCR + ESCR + embedded synchronization code + register + 0x18 + 0x20 + read-write + 0x0000 + + + FEC + Frame end delimiter code + 24 + 8 + + + LEC + Line end delimiter code + 16 + 8 + + + LSC + Line start delimiter code + 8 + 8 + + + FSC + Frame start delimiter code + 0 + 8 + + + + + ESUR + ESUR + embedded synchronization unmask + register + 0x1C + 0x20 + read-write + 0x0000 + + + FEU + Frame end delimiter unmask + 24 + 8 + + + LEU + Line end delimiter unmask + 16 + 8 + + + LSU + Line start delimiter + unmask + 8 + 8 + + + FSU + Frame start delimiter + unmask + 0 + 8 + + + + + CWSTRT + CWSTRT + crop window start + 0x20 + 0x20 + read-write + 0x0000 + + + VST + Vertical start line count + 16 + 13 + + + HOFFCNT + Horizontal offset count + 0 + 14 + + + + + CWSIZE + CWSIZE + crop window size + 0x24 + 0x20 + read-write + 0x0000 + + + VLINE + Vertical line count + 16 + 14 + + + CAPCNT + Capture count + 0 + 14 + + + + + DR + DR + data register + 0x28 + 0x20 + read-only + 0x0000 + + + Byte3 + Data byte 3 + 24 + 8 + + + Byte2 + Data byte 2 + 16 + 8 + + + Byte1 + Data byte 1 + 8 + 8 + + + Byte0 + Data byte 0 + 0 + 8 + + + + + + + OTG1_HS_GLOBAL + USB 1 on the go high speed + USB_OTG_HS + 0x40040000 + + 0x0 + 0x400 + registers + + + + OTG_HS_GOTGCTL + OTG_HS_GOTGCTL + OTG_HS control and status + register + 0x0 + 32 + 0x00000800 + + + SRQSCS + Session request success + 0 + 1 + read-only + + + SRQ + Session request + 1 + 1 + read-write + + + HNGSCS + Host negotiation success + 8 + 1 + read-only + + + HNPRQ + HNP request + 9 + 1 + read-write + + + HSHNPEN + Host set HNP enable + 10 + 1 + read-write + + + DHNPEN + Device HNP enabled + 11 + 1 + read-write + + + CIDSTS + Connector ID status + 16 + 1 + read-only + + + DBCT + Long/short debounce time + 17 + 1 + read-only + + + ASVLD + A-session valid + 18 + 1 + read-only + + + BSVLD + B-session valid + 19 + 1 + read-only + + + EHEN + Embedded host enable + 12 + 1 + read-write + + + + + OTG_HS_GOTGINT + OTG_HS_GOTGINT + OTG_HS interrupt register + 0x4 + 32 + read-write + 0x0 + + + SEDET + Session end detected + 2 + 1 + + + SRSSCHG + Session request success status + change + 8 + 1 + + + HNSSCHG + Host negotiation success status + change + 9 + 1 + + + HNGDET + Host negotiation detected + 17 + 1 + + + ADTOCHG + A-device timeout change + 18 + 1 + + + DBCDNE + Debounce done + 19 + 1 + + + IDCHNG + ID input pin changed + 20 + 1 + + + + + OTG_HS_GAHBCFG + OTG_HS_GAHBCFG + OTG_HS AHB configuration + register + 0x8 + 32 + read-write + 0x0 + + + GINT + Global interrupt mask + 0 + 1 + + + HBSTLEN + Burst length/type + 1 + 4 + + + DMAEN + DMA enable + 5 + 1 + + + TXFELVL + TxFIFO empty level + 7 + 1 + + + PTXFELVL + Periodic TxFIFO empty + level + 8 + 1 + + + + + OTG_HS_GUSBCFG + OTG_HS_GUSBCFG + OTG_HS USB configuration + register + 0xC + 32 + 0x00000A00 + + + TOCAL + FS timeout calibration + 0 + 3 + read-write + + + PHYSEL + USB 2.0 high-speed ULPI PHY or USB 1.1 + full-speed serial transceiver select + 6 + 1 + write-only + + + SRPCAP + SRP-capable + 8 + 1 + read-write + + + HNPCAP + HNP-capable + 9 + 1 + read-write + + + TRDT + USB turnaround time + 10 + 4 + read-write + + + PHYLPCS + PHY Low-power clock select + 15 + 1 + read-write + + + ULPIFSLS + ULPI FS/LS select + 17 + 1 + read-write + + + ULPIAR + ULPI Auto-resume + 18 + 1 + read-write + + + ULPICSM + ULPI Clock SuspendM + 19 + 1 + read-write + + + ULPIEVBUSD + ULPI External VBUS Drive + 20 + 1 + read-write + + + ULPIEVBUSI + ULPI external VBUS + indicator + 21 + 1 + read-write + + + TSDPS + TermSel DLine pulsing + selection + 22 + 1 + read-write + + + PCCI + Indicator complement + 23 + 1 + read-write + + + PTCI + Indicator pass through + 24 + 1 + read-write + + + ULPIIPD + ULPI interface protect + disable + 25 + 1 + read-write + + + FHMOD + Forced host mode + 29 + 1 + read-write + + + FDMOD + Forced peripheral mode + 30 + 1 + read-write + + + + + OTG_HS_GRSTCTL + OTG_HS_GRSTCTL + OTG_HS reset register + 0x10 + 32 + 0x20000000 + + + CSRST + Core soft reset + 0 + 1 + read-write + + + HSRST + HCLK soft reset + 1 + 1 + read-write + + + FCRST + Host frame counter reset + 2 + 1 + read-write + + + RXFFLSH + RxFIFO flush + 4 + 1 + read-write + + + TXFFLSH + TxFIFO flush + 5 + 1 + read-write + + + TXFNUM + TxFIFO number + 6 + 5 + read-write + + + AHBIDL + AHB master idle + 31 + 1 + read-only + + + DMAREQ + DMA request signal enabled for USB OTG + HS + 30 + 1 + read-only + + + + + OTG_HS_GINTSTS + OTG_HS_GINTSTS + OTG_HS core interrupt register + 0x14 + 32 + 0x04000020 + + + CMOD + Current mode of operation + 0 + 1 + read-only + + + MMIS + Mode mismatch interrupt + 1 + 1 + read-write + + + OTGINT + OTG interrupt + 2 + 1 + read-only + + + SOF + Start of frame + 3 + 1 + read-write + + + RXFLVL + RxFIFO nonempty + 4 + 1 + read-only + + + NPTXFE + Nonperiodic TxFIFO empty + 5 + 1 + read-only + + + GINAKEFF + Global IN nonperiodic NAK + effective + 6 + 1 + read-only + + + BOUTNAKEFF + Global OUT NAK effective + 7 + 1 + read-only + + + ESUSP + Early suspend + 10 + 1 + read-write + + + USBSUSP + USB suspend + 11 + 1 + read-write + + + USBRST + USB reset + 12 + 1 + read-write + + + ENUMDNE + Enumeration done + 13 + 1 + read-write + + + ISOODRP + Isochronous OUT packet dropped + interrupt + 14 + 1 + read-write + + + EOPF + End of periodic frame + interrupt + 15 + 1 + read-write + + + IEPINT + IN endpoint interrupt + 18 + 1 + read-only + + + OEPINT + OUT endpoint interrupt + 19 + 1 + read-only + + + IISOIXFR + Incomplete isochronous IN + transfer + 20 + 1 + read-write + + + PXFR_INCOMPISOOUT + Incomplete periodic + transfer + 21 + 1 + read-write + + + DATAFSUSP + Data fetch suspended + 22 + 1 + read-write + + + HPRTINT + Host port interrupt + 24 + 1 + read-only + + + HCINT + Host channels interrupt + 25 + 1 + read-only + + + PTXFE + Periodic TxFIFO empty + 26 + 1 + read-only + + + CIDSCHG + Connector ID status change + 28 + 1 + read-write + + + DISCINT + Disconnect detected + interrupt + 29 + 1 + read-write + + + SRQINT + Session request/new session detected + interrupt + 30 + 1 + read-write + + + WKUINT + Resume/remote wakeup detected + interrupt + 31 + 1 + read-write + + + + + OTG_HS_GINTMSK + OTG_HS_GINTMSK + OTG_HS interrupt mask register + 0x18 + 32 + 0x0 + + + MMISM + Mode mismatch interrupt + mask + 1 + 1 + read-write + + + OTGINT + OTG interrupt mask + 2 + 1 + read-write + + + SOFM + Start of frame mask + 3 + 1 + read-write + + + RXFLVLM + Receive FIFO nonempty mask + 4 + 1 + read-write + + + NPTXFEM + Nonperiodic TxFIFO empty + mask + 5 + 1 + read-write + + + GINAKEFFM + Global nonperiodic IN NAK effective + mask + 6 + 1 + read-write + + + GONAKEFFM + Global OUT NAK effective + mask + 7 + 1 + read-write + + + ESUSPM + Early suspend mask + 10 + 1 + read-write + + + USBSUSPM + USB suspend mask + 11 + 1 + read-write + + + USBRST + USB reset mask + 12 + 1 + read-write + + + ENUMDNEM + Enumeration done mask + 13 + 1 + read-write + + + ISOODRPM + Isochronous OUT packet dropped interrupt + mask + 14 + 1 + read-write + + + EOPFM + End of periodic frame interrupt + mask + 15 + 1 + read-write + + + IEPINT + IN endpoints interrupt + mask + 18 + 1 + read-write + + + OEPINT + OUT endpoints interrupt + mask + 19 + 1 + read-write + + + IISOIXFRM + Incomplete isochronous IN transfer + mask + 20 + 1 + read-write + + + PXFRM_IISOOXFRM + Incomplete periodic transfer + mask + 21 + 1 + read-write + + + FSUSPM + Data fetch suspended mask + 22 + 1 + read-write + + + PRTIM + Host port interrupt mask + 24 + 1 + read-only + + + HCIM + Host channels interrupt + mask + 25 + 1 + read-write + + + PTXFEM + Periodic TxFIFO empty mask + 26 + 1 + read-write + + + CIDSCHGM + Connector ID status change + mask + 28 + 1 + read-write + + + DISCINT + Disconnect detected interrupt + mask + 29 + 1 + read-write + + + SRQIM + Session request/new session detected + interrupt mask + 30 + 1 + read-write + + + WUIM + Resume/remote wakeup detected interrupt + mask + 31 + 1 + read-write + + + RSTDE + Reset detected interrupt + mask + 23 + 1 + read-write + + + LPMINTM + LPM interrupt mask + 27 + 1 + read-write + + + + + OTG_HS_GRXSTSR_Host + OTG_HS_GRXSTSR_Host + OTG_HS Receive status debug read register + (host mode) + 0x1C + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXSTSP_Host + OTG_HS_GRXSTSP_Host + OTG_HS status read and pop register (host + mode) + 0x20 + 32 + read-only + 0x0 + + + CHNUM + Channel number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + + + OTG_HS_GRXFSIZ + OTG_HS_GRXFSIZ + OTG_HS Receive FIFO size + register + 0x24 + 32 + read-write + 0x00000200 + + + RXFD + RxFIFO depth + 0 + 16 + + + + + OTG_HS_HNPTXFSIZ_Host + OTG_HS_HNPTXFSIZ_Host + OTG_HS nonperiodic transmit FIFO size + register (host mode) + 0x28 + 32 + read-write + 0x00000200 + + + NPTXFSA + Nonperiodic transmit RAM start + address + 0 + 16 + + + NPTXFD + Nonperiodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF0_Device + OTG_HS_DIEPTXF0_Device + Endpoint 0 transmit FIFO size (peripheral + mode) + OTG_HS_HNPTXFSIZ_Host + 0x28 + 32 + read-write + 0x00000200 + + + TX0FSA + Endpoint 0 transmit RAM start + address + 0 + 16 + + + TX0FD + Endpoint 0 TxFIFO depth + 16 + 16 + + + + + OTG_HS_GNPTXSTS + OTG_HS_GNPTXSTS + OTG_HS nonperiodic transmit FIFO/queue + status register + 0x2C + 32 + read-only + 0x00080200 + + + NPTXFSAV + Nonperiodic TxFIFO space + available + 0 + 16 + + + NPTQXSAV + Nonperiodic transmit request queue space + available + 16 + 8 + + + NPTXQTOP + Top of the nonperiodic transmit request + queue + 24 + 7 + + + + + OTG_HS_GCCFG + OTG_HS_GCCFG + OTG_HS general core configuration + register + 0x38 + 32 + read-write + 0x0 + + + PWRDWN + Power down + 16 + 1 + + + BCDEN + Battery charging detector (BCD) + enable + 17 + 1 + + + DCDEN + Data contact detection (DCD) mode + enable + 18 + 1 + + + PDEN + Primary detection (PD) mode + enable + 19 + 1 + + + SDEN + Secondary detection (SD) mode + enable + 20 + 1 + + + VBDEN + USB VBUS detection enable + 21 + 1 + + + DCDET + Data contact detection (DCD) + status + 0 + 1 + + + PDET + Primary detection (PD) + status + 1 + 1 + + + SDET + Secondary detection (SD) + status + 2 + 1 + + + PS2DET + DM pull-up detection + status + 3 + 1 + + + + + OTG_HS_CID + OTG_HS_CID + OTG_HS core ID register + 0x3C + 32 + read-write + 0x00001200 + + + PRODUCT_ID + Product ID field + 0 + 32 + + + + + OTG_HS_HPTXFSIZ + OTG_HS_HPTXFSIZ + OTG_HS Host periodic transmit FIFO size + register + 0x100 + 32 + read-write + 0x02000600 + + + PTXSA + Host periodic TxFIFO start + address + 0 + 16 + + + PTXFD + Host periodic TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF1 + OTG_HS_DIEPTXF1 + OTG_HS device IN endpoint transmit FIFO size + register + 0x104 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF2 + OTG_HS_DIEPTXF2 + OTG_HS device IN endpoint transmit FIFO size + register + 0x108 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF3 + OTG_HS_DIEPTXF3 + OTG_HS device IN endpoint transmit FIFO size + register + 0x11C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF4 + OTG_HS_DIEPTXF4 + OTG_HS device IN endpoint transmit FIFO size + register + 0x120 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF5 + OTG_HS_DIEPTXF5 + OTG_HS device IN endpoint transmit FIFO size + register + 0x124 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF6 + OTG_HS_DIEPTXF6 + OTG_HS device IN endpoint transmit FIFO size + register + 0x128 + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_DIEPTXF7 + OTG_HS_DIEPTXF7 + OTG_HS device IN endpoint transmit FIFO size + register + 0x12C + 32 + read-write + 0x02000400 + + + INEPTXSA + IN endpoint FIFOx transmit RAM start + address + 0 + 16 + + + INEPTXFD + IN endpoint TxFIFO depth + 16 + 16 + + + + + OTG_HS_GRXSTSR_Device + OTG_HS_GRXSTSR_Device + OTG_HS Receive status debug read register + (peripheral mode mode) + OTG_HS_GRXSTSR_Host + 0x1C + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GRXSTSP_Device + OTG_HS_GRXSTSP_Device + OTG_HS status read and pop register + (peripheral mode) + OTG_HS_GRXSTSP_Host + 0x20 + 32 + read-only + 0x0 + + + EPNUM + Endpoint number + 0 + 4 + + + BCNT + Byte count + 4 + 11 + + + DPID + Data PID + 15 + 2 + + + PKTSTS + Packet status + 17 + 4 + + + FRMNUM + Frame number + 21 + 4 + + + + + OTG_HS_GLPMCFG + OTG_HS_GLPMCFG + OTG core LPM configuration + register + 0x54 + 32 + 0x0 + + + LPMEN + LPM support enable + 0 + 1 + read-write + + + LPMACK + LPM token acknowledge + enable + 1 + 1 + read-write + + + BESL + Best effort service + latency + 2 + 4 + read-only + + + REMWAKE + bRemoteWake value + 6 + 1 + read-only + + + L1SSEN + L1 Shallow Sleep enable + 7 + 1 + read-write + + + BESLTHRS + BESL threshold + 8 + 4 + read-write + + + L1DSEN + L1 deep sleep enable + 12 + 1 + read-write + + + LPMRST + LPM response + 13 + 2 + read-only + + + SLPSTS + Port sleep status + 15 + 1 + read-only + + + L1RSMOK + Sleep State Resume OK + 16 + 1 + read-only + + + LPMCHIDX + LPM Channel Index + 17 + 4 + read-write + + + LPMRCNT + LPM retry count + 21 + 3 + read-write + + + SNDLPM + Send LPM transaction + 24 + 1 + read-write + + + LPMRCNTSTS + LPM retry count status + 25 + 3 + read-only + + + ENBESL + Enable best effort service + latency + 28 + 1 + read-write + + + + + + + OTG2_HS_GLOBAL + 0x40080000 + + OTG_HS_EP1_OUT + OTG_HS out global interrupt + 74 + + + OTG_HS_EP1_IN + OTG_HS in global interrupt + 75 + + + OTG_HS_WKUP + OTG_HS wakeup interrupt + 76 + + + OTG_HS + OTG_HS global interrupt + 77 + + + OTG_FS_EP1_OUT + OTG_FS out global interrupt + 98 + + + OTG_FS_EP1_IN + OTG_FS in global interrupt + 99 + + + OTG_FS_WKUP + OTG_FS wakeup + 100 + + + + OTG1_HS_HOST + USB 1 on the go high speed + USB_OTG_HS + 0x40040400 + + 0x0 + 0x400 + registers + + + OTG_FS + OTG_FS global interrupt + 101 + + + + OTG_HS_HCFG + OTG_HS_HCFG + OTG_HS host configuration + register + 0x0 + 32 + 0x0 + + + FSLSPCS + FS/LS PHY clock select + 0 + 2 + read-write + + + FSLSS + FS- and LS-only support + 2 + 1 + read-only + + + + + OTG_HS_HFIR + OTG_HS_HFIR + OTG_HS Host frame interval + register + 0x4 + 32 + read-write + 0x0000EA60 + + + FRIVL + Frame interval + 0 + 16 + + + + + OTG_HS_HFNUM + OTG_HS_HFNUM + OTG_HS host frame number/frame time + remaining register + 0x8 + 32 + read-only + 0x00003FFF + + + FRNUM + Frame number + 0 + 16 + + + FTREM + Frame time remaining + 16 + 16 + + + + + OTG_HS_HPTXSTS + OTG_HS_HPTXSTS + OTG_HS_Host periodic transmit FIFO/queue + status register + 0x10 + 32 + 0x00080100 + + + PTXFSAVL + Periodic transmit data FIFO space + available + 0 + 16 + read-write + + + PTXQSAV + Periodic transmit request queue space + available + 16 + 8 + read-only + + + PTXQTOP + Top of the periodic transmit request + queue + 24 + 8 + read-only + + + + + OTG_HS_HAINT + OTG_HS_HAINT + OTG_HS Host all channels interrupt + register + 0x14 + 32 + read-only + 0x0 + + + HAINT + Channel interrupts + 0 + 16 + + + + + OTG_HS_HAINTMSK + OTG_HS_HAINTMSK + OTG_HS host all channels interrupt mask + register + 0x18 + 32 + read-write + 0x0 + + + HAINTM + Channel interrupt mask + 0 + 16 + + + + + OTG_HS_HPRT + OTG_HS_HPRT + OTG_HS host port control and status + register + 0x40 + 32 + 0x0 + + + PCSTS + Port connect status + 0 + 1 + read-only + + + PCDET + Port connect detected + 1 + 1 + read-write + + + PENA + Port enable + 2 + 1 + read-write + + + PENCHNG + Port enable/disable change + 3 + 1 + read-write + + + POCA + Port overcurrent active + 4 + 1 + read-only + + + POCCHNG + Port overcurrent change + 5 + 1 + read-write + + + PRES + Port resume + 6 + 1 + read-write + + + PSUSP + Port suspend + 7 + 1 + read-write + + + PRST + Port reset + 8 + 1 + read-write + + + PLSTS + Port line status + 10 + 2 + read-only + + + PPWR + Port power + 12 + 1 + read-write + + + PTCTL + Port test control + 13 + 4 + read-write + + + PSPD + Port speed + 17 + 2 + read-only + + + + + OTG_HS_HCCHAR0 + OTG_HS_HCCHAR0 + OTG_HS host channel-0 characteristics + register + 0x100 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR1 + OTG_HS_HCCHAR1 + OTG_HS host channel-1 characteristics + register + 0x120 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR2 + OTG_HS_HCCHAR2 + OTG_HS host channel-2 characteristics + register + 0x140 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR3 + OTG_HS_HCCHAR3 + OTG_HS host channel-3 characteristics + register + 0x160 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR4 + OTG_HS_HCCHAR4 + OTG_HS host channel-4 characteristics + register + 0x180 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR5 + OTG_HS_HCCHAR5 + OTG_HS host channel-5 characteristics + register + 0x1A0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR6 + OTG_HS_HCCHAR6 + OTG_HS host channel-6 characteristics + register + 0x1C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR7 + OTG_HS_HCCHAR7 + OTG_HS host channel-7 characteristics + register + 0x1E0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR8 + OTG_HS_HCCHAR8 + OTG_HS host channel-8 characteristics + register + 0x200 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR9 + OTG_HS_HCCHAR9 + OTG_HS host channel-9 characteristics + register + 0x220 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR10 + OTG_HS_HCCHAR10 + OTG_HS host channel-10 characteristics + register + 0x240 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCCHAR11 + OTG_HS_HCCHAR11 + OTG_HS host channel-11 characteristics + register + 0x260 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT0 + OTG_HS_HCSPLT0 + OTG_HS host channel-0 split control + register + 0x104 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT1 + OTG_HS_HCSPLT1 + OTG_HS host channel-1 split control + register + 0x124 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT2 + OTG_HS_HCSPLT2 + OTG_HS host channel-2 split control + register + 0x144 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT3 + OTG_HS_HCSPLT3 + OTG_HS host channel-3 split control + register + 0x164 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT4 + OTG_HS_HCSPLT4 + OTG_HS host channel-4 split control + register + 0x184 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT5 + OTG_HS_HCSPLT5 + OTG_HS host channel-5 split control + register + 0x1A4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT6 + OTG_HS_HCSPLT6 + OTG_HS host channel-6 split control + register + 0x1C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT7 + OTG_HS_HCSPLT7 + OTG_HS host channel-7 split control + register + 0x1E4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT8 + OTG_HS_HCSPLT8 + OTG_HS host channel-8 split control + register + 0x204 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT9 + OTG_HS_HCSPLT9 + OTG_HS host channel-9 split control + register + 0x224 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT10 + OTG_HS_HCSPLT10 + OTG_HS host channel-10 split control + register + 0x244 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCSPLT11 + OTG_HS_HCSPLT11 + OTG_HS host channel-11 split control + register + 0x264 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT0 + OTG_HS_HCINT0 + OTG_HS host channel-11 interrupt + register + 0x108 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT1 + OTG_HS_HCINT1 + OTG_HS host channel-1 interrupt + register + 0x128 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT2 + OTG_HS_HCINT2 + OTG_HS host channel-2 interrupt + register + 0x148 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT3 + OTG_HS_HCINT3 + OTG_HS host channel-3 interrupt + register + 0x168 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT4 + OTG_HS_HCINT4 + OTG_HS host channel-4 interrupt + register + 0x188 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT5 + OTG_HS_HCINT5 + OTG_HS host channel-5 interrupt + register + 0x1A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT6 + OTG_HS_HCINT6 + OTG_HS host channel-6 interrupt + register + 0x1C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT7 + OTG_HS_HCINT7 + OTG_HS host channel-7 interrupt + register + 0x1E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT8 + OTG_HS_HCINT8 + OTG_HS host channel-8 interrupt + register + 0x208 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT9 + OTG_HS_HCINT9 + OTG_HS host channel-9 interrupt + register + 0x228 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT10 + OTG_HS_HCINT10 + OTG_HS host channel-10 interrupt + register + 0x248 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINT11 + OTG_HS_HCINT11 + OTG_HS host channel-11 interrupt + register + 0x268 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK0 + OTG_HS_HCINTMSK0 + OTG_HS host channel-11 interrupt mask + register + 0x10C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK1 + OTG_HS_HCINTMSK1 + OTG_HS host channel-1 interrupt mask + register + 0x12C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK2 + OTG_HS_HCINTMSK2 + OTG_HS host channel-2 interrupt mask + register + 0x14C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK3 + OTG_HS_HCINTMSK3 + OTG_HS host channel-3 interrupt mask + register + 0x16C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK4 + OTG_HS_HCINTMSK4 + OTG_HS host channel-4 interrupt mask + register + 0x18C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK5 + OTG_HS_HCINTMSK5 + OTG_HS host channel-5 interrupt mask + register + 0x1AC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK6 + OTG_HS_HCINTMSK6 + OTG_HS host channel-6 interrupt mask + register + 0x1CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK7 + OTG_HS_HCINTMSK7 + OTG_HS host channel-7 interrupt mask + register + 0x1EC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK8 + OTG_HS_HCINTMSK8 + OTG_HS host channel-8 interrupt mask + register + 0x20C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK9 + OTG_HS_HCINTMSK9 + OTG_HS host channel-9 interrupt mask + register + 0x22C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK10 + OTG_HS_HCINTMSK10 + OTG_HS host channel-10 interrupt mask + register + 0x24C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCINTMSK11 + OTG_HS_HCINTMSK11 + OTG_HS host channel-11 interrupt mask + register + 0x26C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + response received interrupt + mask + 6 + 1 + + + TXERRM + Transaction error mask + 7 + 1 + + + BBERRM + Babble error mask + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ0 + OTG_HS_HCTSIZ0 + OTG_HS host channel-11 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ1 + OTG_HS_HCTSIZ1 + OTG_HS host channel-1 transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ2 + OTG_HS_HCTSIZ2 + OTG_HS host channel-2 transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ3 + OTG_HS_HCTSIZ3 + OTG_HS host channel-3 transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ4 + OTG_HS_HCTSIZ4 + OTG_HS host channel-4 transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ5 + OTG_HS_HCTSIZ5 + OTG_HS host channel-5 transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ6 + OTG_HS_HCTSIZ6 + OTG_HS host channel-6 transfer size + register + 0x1D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ7 + OTG_HS_HCTSIZ7 + OTG_HS host channel-7 transfer size + register + 0x1F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ8 + OTG_HS_HCTSIZ8 + OTG_HS host channel-8 transfer size + register + 0x210 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ9 + OTG_HS_HCTSIZ9 + OTG_HS host channel-9 transfer size + register + 0x230 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ10 + OTG_HS_HCTSIZ10 + OTG_HS host channel-10 transfer size + register + 0x250 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCTSIZ11 + OTG_HS_HCTSIZ11 + OTG_HS host channel-11 transfer size + register + 0x270 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA0 + OTG_HS_HCDMA0 + OTG_HS host channel-0 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA1 + OTG_HS_HCDMA1 + OTG_HS host channel-1 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA2 + OTG_HS_HCDMA2 + OTG_HS host channel-2 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA3 + OTG_HS_HCDMA3 + OTG_HS host channel-3 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA4 + OTG_HS_HCDMA4 + OTG_HS host channel-4 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA5 + OTG_HS_HCDMA5 + OTG_HS host channel-5 DMA address + register + 0x1B4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA6 + OTG_HS_HCDMA6 + OTG_HS host channel-6 DMA address + register + 0x1D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA7 + OTG_HS_HCDMA7 + OTG_HS host channel-7 DMA address + register + 0x1F4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA8 + OTG_HS_HCDMA8 + OTG_HS host channel-8 DMA address + register + 0x214 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA9 + OTG_HS_HCDMA9 + OTG_HS host channel-9 DMA address + register + 0x234 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA10 + OTG_HS_HCDMA10 + OTG_HS host channel-10 DMA address + register + 0x254 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCDMA11 + OTG_HS_HCDMA11 + OTG_HS host channel-11 DMA address + register + 0x274 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR12 + OTG_HS_HCCHAR12 + OTG_HS host channel-12 characteristics + register + 0x278 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT12 + OTG_HS_HCSPLT12 + OTG_HS host channel-12 split control + register + 0x27C + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT12 + OTG_HS_HCINT12 + OTG_HS host channel-12 interrupt + register + 0x280 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK12 + OTG_HS_HCINTMSK12 + OTG_HS host channel-12 interrupt mask + register + 0x284 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ12 + OTG_HS_HCTSIZ12 + OTG_HS host channel-12 transfer size + register + 0x288 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA12 + OTG_HS_HCDMA12 + OTG_HS host channel-12 DMA address + register + 0x28C + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR13 + OTG_HS_HCCHAR13 + OTG_HS host channel-13 characteristics + register + 0x290 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT13 + OTG_HS_HCSPLT13 + OTG_HS host channel-13 split control + register + 0x294 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT13 + OTG_HS_HCINT13 + OTG_HS host channel-13 interrupt + register + 0x298 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK13 + OTG_HS_HCINTMSK13 + OTG_HS host channel-13 interrupt mask + register + 0x29C + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALLM response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ13 + OTG_HS_HCTSIZ13 + OTG_HS host channel-13 transfer size + register + 0x2A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA13 + OTG_HS_HCDMA13 + OTG_HS host channel-13 DMA address + register + 0x2A4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR14 + OTG_HS_HCCHAR14 + OTG_HS host channel-14 characteristics + register + 0x2A8 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT14 + OTG_HS_HCSPLT14 + OTG_HS host channel-14 split control + register + 0x2AC + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT14 + OTG_HS_HCINT14 + OTG_HS host channel-14 interrupt + register + 0x2B0 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK14 + OTG_HS_HCINTMSK14 + OTG_HS host channel-14 interrupt mask + register + 0x2B4 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALLM + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAKM response received interrupt + mask + 4 + 1 + + + ACKM + ACKM response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ14 + OTG_HS_HCTSIZ14 + OTG_HS host channel-14 transfer size + register + 0x2B8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA14 + OTG_HS_HCDMA14 + OTG_HS host channel-14 DMA address + register + 0x2BC + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_HCCHAR15 + OTG_HS_HCCHAR15 + OTG_HS host channel-15 characteristics + register + 0x2C0 + 32 + read-write + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + + + EPNUM + Endpoint number + 11 + 4 + + + EPDIR + Endpoint direction + 15 + 1 + + + LSDEV + Low-speed device + 17 + 1 + + + EPTYP + Endpoint type + 18 + 2 + + + MC + Multi Count (MC) / Error Count + (EC) + 20 + 2 + + + DAD + Device address + 22 + 7 + + + ODDFRM + Odd frame + 29 + 1 + + + CHDIS + Channel disable + 30 + 1 + + + CHENA + Channel enable + 31 + 1 + + + + + OTG_HS_HCSPLT15 + OTG_HS_HCSPLT15 + OTG_HS host channel-15 split control + register + 0x2C4 + 32 + read-write + 0x0 + + + PRTADDR + Port address + 0 + 7 + + + HUBADDR + Hub address + 7 + 7 + + + XACTPOS + XACTPOS + 14 + 2 + + + COMPLSPLT + Do complete split + 16 + 1 + + + SPLITEN + Split enable + 31 + 1 + + + + + OTG_HS_HCINT15 + OTG_HS_HCINT15 + OTG_HS host channel-15 interrupt + register + 0x2C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + 0 + 1 + + + CHH + Channel halted + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received + interrupt + 3 + 1 + + + NAK + NAK response received + interrupt + 4 + 1 + + + ACK + ACK response received/transmitted + interrupt + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERR + Transaction error + 7 + 1 + + + BBERR + Babble error + 8 + 1 + + + FRMOR + Frame overrun + 9 + 1 + + + DTERR + Data toggle error + 10 + 1 + + + + + OTG_HS_HCINTMSK15 + OTG_HS_HCINTMSK15 + OTG_HS host channel-15 interrupt mask + register + 0x2CC + 32 + read-write + 0x0 + + + XFRCM + Transfer completed mask + 0 + 1 + + + CHHM + Channel halted mask + 1 + 1 + + + AHBERR + AHB error + 2 + 1 + + + STALL + STALL response received interrupt + mask + 3 + 1 + + + NAKM + NAK response received interrupt + mask + 4 + 1 + + + ACKM + ACK response received/transmitted + interrupt mask + 5 + 1 + + + NYET + Response received + interrupt + 6 + 1 + + + TXERRM + Transaction error + 7 + 1 + + + BBERRM + Babble error + 8 + 1 + + + FRMORM + Frame overrun mask + 9 + 1 + + + DTERRM + Data toggle error mask + 10 + 1 + + + + + OTG_HS_HCTSIZ15 + OTG_HS_HCTSIZ15 + OTG_HS host channel-15 transfer size + register + 0x2D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + DPID + Data PID + 29 + 2 + + + + + OTG_HS_HCDMA15 + OTG_HS_HCDMA15 + OTG_HS host channel-15 DMA address + register + 0x2D4 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + + + OTG2_HS_HOST + 0x40080400 + + + OTG1_HS_DEVICE + USB 1 on the go high speed + USB_OTG_HS + 0x40040800 + + 0x0 + 0x400 + registers + + + + OTG_HS_DCFG + OTG_HS_DCFG + OTG_HS device configuration + register + 0x0 + 32 + read-write + 0x02200000 + + + DSPD + Device speed + 0 + 2 + + + NZLSOHSK + Nonzero-length status OUT + handshake + 2 + 1 + + + DAD + Device address + 4 + 7 + + + PFIVL + Periodic (micro)frame + interval + 11 + 2 + + + PERSCHIVL + Periodic scheduling + interval + 24 + 2 + + + + + OTG_HS_DCTL + OTG_HS_DCTL + OTG_HS device control register + 0x4 + 32 + 0x0 + + + RWUSIG + Remote wakeup signaling + 0 + 1 + read-write + + + SDIS + Soft disconnect + 1 + 1 + read-write + + + GINSTS + Global IN NAK status + 2 + 1 + read-only + + + GONSTS + Global OUT NAK status + 3 + 1 + read-only + + + TCTL + Test control + 4 + 3 + read-write + + + SGINAK + Set global IN NAK + 7 + 1 + write-only + + + CGINAK + Clear global IN NAK + 8 + 1 + write-only + + + SGONAK + Set global OUT NAK + 9 + 1 + write-only + + + CGONAK + Clear global OUT NAK + 10 + 1 + write-only + + + POPRGDNE + Power-on programming done + 11 + 1 + read-write + + + + + OTG_HS_DSTS + OTG_HS_DSTS + OTG_HS device status register + 0x8 + 32 + read-only + 0x00000010 + + + SUSPSTS + Suspend status + 0 + 1 + + + ENUMSPD + Enumerated speed + 1 + 2 + + + EERR + Erratic error + 3 + 1 + + + FNSOF + Frame number of the received + SOF + 8 + 14 + + + + + OTG_HS_DIEPMSK + OTG_HS_DIEPMSK + OTG_HS device IN endpoint common interrupt + mask register + 0x10 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + TOM + Timeout condition mask (nonisochronous + endpoints) + 3 + 1 + + + ITTXFEMSK + IN token received when TxFIFO empty + mask + 4 + 1 + + + INEPNMM + IN token received with EP mismatch + mask + 5 + 1 + + + INEPNEM + IN endpoint NAK effective + mask + 6 + 1 + + + TXFURM + FIFO underrun mask + 8 + 1 + + + BIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DOEPMSK + OTG_HS_DOEPMSK + OTG_HS device OUT endpoint common interrupt + mask register + 0x14 + 32 + read-write + 0x0 + + + XFRCM + Transfer completed interrupt + mask + 0 + 1 + + + EPDM + Endpoint disabled interrupt + mask + 1 + 1 + + + STUPM + SETUP phase done mask + 3 + 1 + + + OTEPDM + OUT token received when endpoint + disabled mask + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets received + mask + 6 + 1 + + + OPEM + OUT packet error mask + 8 + 1 + + + BOIM + BNA interrupt mask + 9 + 1 + + + + + OTG_HS_DAINT + OTG_HS_DAINT + OTG_HS device all endpoints interrupt + register + 0x18 + 32 + read-only + 0x0 + + + IEPINT + IN endpoint interrupt bits + 0 + 16 + + + OEPINT + OUT endpoint interrupt + bits + 16 + 16 + + + + + OTG_HS_DAINTMSK + OTG_HS_DAINTMSK + OTG_HS all endpoints interrupt mask + register + 0x1C + 32 + read-write + 0x0 + + + IEPM + IN EP interrupt mask bits + 0 + 16 + + + OEPM + OUT EP interrupt mask bits + 16 + 16 + + + + + OTG_HS_DVBUSDIS + OTG_HS_DVBUSDIS + OTG_HS device VBUS discharge time + register + 0x28 + 32 + read-write + 0x000017D7 + + + VBUSDT + Device VBUS discharge time + 0 + 16 + + + + + OTG_HS_DVBUSPULSE + OTG_HS_DVBUSPULSE + OTG_HS device VBUS pulsing time + register + 0x2C + 32 + read-write + 0x000005B8 + + + DVBUSP + Device VBUS pulsing time + 0 + 12 + + + + + OTG_HS_DTHRCTL + OTG_HS_DTHRCTL + OTG_HS Device threshold control + register + 0x30 + 32 + read-write + 0x0 + + + NONISOTHREN + Nonisochronous IN endpoints threshold + enable + 0 + 1 + + + ISOTHREN + ISO IN endpoint threshold + enable + 1 + 1 + + + TXTHRLEN + Transmit threshold length + 2 + 9 + + + RXTHREN + Receive threshold enable + 16 + 1 + + + RXTHRLEN + Receive threshold length + 17 + 9 + + + ARPEN + Arbiter parking enable + 27 + 1 + + + + + OTG_HS_DIEPEMPMSK + OTG_HS_DIEPEMPMSK + OTG_HS device IN endpoint FIFO empty + interrupt mask register + 0x34 + 32 + read-write + 0x0 + + + INEPTXFEM + IN EP Tx FIFO empty interrupt mask + bits + 0 + 16 + + + + + OTG_HS_DEACHINT + OTG_HS_DEACHINT + OTG_HS device each endpoint interrupt + register + 0x38 + 32 + read-write + 0x0 + + + IEP1INT + IN endpoint 1interrupt bit + 1 + 1 + + + OEP1INT + OUT endpoint 1 interrupt + bit + 17 + 1 + + + + + OTG_HS_DEACHINTMSK + OTG_HS_DEACHINTMSK + OTG_HS device each endpoint interrupt + register mask + 0x3C + 32 + read-write + 0x0 + + + IEP1INTM + IN Endpoint 1 interrupt mask + bit + 1 + 1 + + + OEP1INTM + OUT Endpoint 1 interrupt mask + bit + 17 + 1 + + + + + OTG_HS_DIEPCTL0 + OTG_HS_DIEPCTL0 + OTG device endpoint-0 control + register + 0x100 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL1 + OTG_HS_DIEPCTL1 + OTG device endpoint-1 control + register + 0x120 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL2 + OTG_HS_DIEPCTL2 + OTG device endpoint-2 control + register + 0x140 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL3 + OTG_HS_DIEPCTL3 + OTG device endpoint-3 control + register + 0x160 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL4 + OTG_HS_DIEPCTL4 + OTG device endpoint-4 control + register + 0x180 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL5 + OTG_HS_DIEPCTL5 + OTG device endpoint-5 control + register + 0x1A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL6 + OTG_HS_DIEPCTL6 + OTG device endpoint-6 control + register + 0x1C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPCTL7 + OTG_HS_DIEPCTL7 + OTG device endpoint-7 control + register + 0x1E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even/odd frame + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + TXFNUM + TxFIFO number + 22 + 4 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DIEPINT0 + OTG_HS_DIEPINT0 + OTG device endpoint-0 interrupt + register + 0x108 + 32 + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT1 + OTG_HS_DIEPINT1 + OTG device endpoint-1 interrupt + register + 0x128 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT2 + OTG_HS_DIEPINT2 + OTG device endpoint-2 interrupt + register + 0x148 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT3 + OTG_HS_DIEPINT3 + OTG device endpoint-3 interrupt + register + 0x168 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT4 + OTG_HS_DIEPINT4 + OTG device endpoint-4 interrupt + register + 0x188 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT5 + OTG_HS_DIEPINT5 + OTG device endpoint-5 interrupt + register + 0x1A8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT6 + OTG_HS_DIEPINT6 + OTG device endpoint-6 interrupt + register + 0x1C8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPINT7 + OTG_HS_DIEPINT7 + OTG device endpoint-7 interrupt + register + 0x1E8 + 32 + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + read-write + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + read-write + + + TOC + Timeout condition + 3 + 1 + read-write + + + ITTXFE + IN token received when TxFIFO is + empty + 4 + 1 + read-write + + + INEPNE + IN endpoint NAK effective + 6 + 1 + read-write + + + TXFE + Transmit FIFO empty + 7 + 1 + read-only + + + TXFIFOUDRN + Transmit Fifo Underrun + 8 + 1 + read-write + + + BNA + Buffer not available + interrupt + 9 + 1 + read-write + + + PKTDRPSTS + Packet dropped status + 11 + 1 + read-write + + + BERR + Babble error interrupt + 12 + 1 + read-write + + + NAK + NAK interrupt + 13 + 1 + read-write + + + + + OTG_HS_DIEPTSIZ0 + OTG_HS_DIEPTSIZ0 + OTG_HS device IN endpoint 0 transfer size + register + 0x110 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 2 + + + + + OTG_HS_DIEPDMA1 + OTG_HS_DIEPDMA1 + OTG_HS device endpoint-1 DMA address + register + 0x114 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA2 + OTG_HS_DIEPDMA2 + OTG_HS device endpoint-2 DMA address + register + 0x134 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA3 + OTG_HS_DIEPDMA3 + OTG_HS device endpoint-3 DMA address + register + 0x154 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA4 + OTG_HS_DIEPDMA4 + OTG_HS device endpoint-4 DMA address + register + 0x174 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DIEPDMA5 + OTG_HS_DIEPDMA5 + OTG_HS device endpoint-5 DMA address + register + 0x194 + 32 + read-write + 0x0 + + + DMAADDR + DMA address + 0 + 32 + + + + + OTG_HS_DTXFSTS0 + OTG_HS_DTXFSTS0 + OTG_HS device IN endpoint transmit FIFO + status register + 0x118 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS1 + OTG_HS_DTXFSTS1 + OTG_HS device IN endpoint transmit FIFO + status register + 0x138 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS2 + OTG_HS_DTXFSTS2 + OTG_HS device IN endpoint transmit FIFO + status register + 0x158 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS3 + OTG_HS_DTXFSTS3 + OTG_HS device IN endpoint transmit FIFO + status register + 0x178 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS4 + OTG_HS_DTXFSTS4 + OTG_HS device IN endpoint transmit FIFO + status register + 0x198 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DTXFSTS5 + OTG_HS_DTXFSTS5 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1B8 + 32 + read-only + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ1 + OTG_HS_DIEPTSIZ1 + OTG_HS device endpoint transfer size + register + 0x130 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ2 + OTG_HS_DIEPTSIZ2 + OTG_HS device endpoint transfer size + register + 0x150 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ3 + OTG_HS_DIEPTSIZ3 + OTG_HS device endpoint transfer size + register + 0x170 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ4 + OTG_HS_DIEPTSIZ4 + OTG_HS device endpoint transfer size + register + 0x190 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ5 + OTG_HS_DIEPTSIZ5 + OTG_HS device endpoint transfer size + register + 0x1B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DOEPCTL0 + OTG_HS_DOEPCTL0 + OTG_HS device control OUT endpoint 0 control + register + 0x300 + 32 + 0x00008000 + + + MPSIZ + Maximum packet size + 0 + 2 + read-only + + + USBAEP + USB active endpoint + 15 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-only + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-only + + + EPENA + Endpoint enable + 31 + 1 + write-only + + + + + OTG_HS_DOEPCTL1 + OTG_HS_DOEPCTL1 + OTG device endpoint-1 control + register + 0x320 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL2 + OTG_HS_DOEPCTL2 + OTG device endpoint-2 control + register + 0x340 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL3 + OTG_HS_DOEPCTL3 + OTG device endpoint-3 control + register + 0x360 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPINT0 + OTG_HS_DOEPINT0 + OTG_HS device endpoint-0 interrupt + register + 0x308 + 32 + read-write + 0x00000080 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT1 + OTG_HS_DOEPINT1 + OTG_HS device endpoint-1 interrupt + register + 0x328 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT2 + OTG_HS_DOEPINT2 + OTG_HS device endpoint-2 interrupt + register + 0x348 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT3 + OTG_HS_DOEPINT3 + OTG_HS device endpoint-3 interrupt + register + 0x368 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT4 + OTG_HS_DOEPINT4 + OTG_HS device endpoint-4 interrupt + register + 0x388 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT5 + OTG_HS_DOEPINT5 + OTG_HS device endpoint-5 interrupt + register + 0x3A8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT6 + OTG_HS_DOEPINT6 + OTG_HS device endpoint-6 interrupt + register + 0x3C8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPINT7 + OTG_HS_DOEPINT7 + OTG_HS device endpoint-7 interrupt + register + 0x3E8 + 32 + read-write + 0x0 + + + XFRC + Transfer completed + interrupt + 0 + 1 + + + EPDISD + Endpoint disabled + interrupt + 1 + 1 + + + STUP + SETUP phase done + 3 + 1 + + + OTEPDIS + OUT token received when endpoint + disabled + 4 + 1 + + + B2BSTUP + Back-to-back SETUP packets + received + 6 + 1 + + + NYET + NYET interrupt + 14 + 1 + + + + + OTG_HS_DOEPTSIZ0 + OTG_HS_DOEPTSIZ0 + OTG_HS device endpoint-0 transfer size + register + 0x310 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 7 + + + PKTCNT + Packet count + 19 + 1 + + + STUPCNT + SETUP packet count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ1 + OTG_HS_DOEPTSIZ1 + OTG_HS device endpoint-1 transfer size + register + 0x330 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ2 + OTG_HS_DOEPTSIZ2 + OTG_HS device endpoint-2 transfer size + register + 0x350 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ3 + OTG_HS_DOEPTSIZ3 + OTG_HS device endpoint-3 transfer size + register + 0x370 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ4 + OTG_HS_DOEPTSIZ4 + OTG_HS device endpoint-4 transfer size + register + 0x390 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DIEPTSIZ6 + OTG_HS_DIEPTSIZ6 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPCTL5 + 0x1A0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS6 + OTG_HS_DTXFSTS6 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1A4 + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DIEPTSIZ7 + OTG_HS_DIEPTSIZ7 + OTG_HS device endpoint transfer size + register + OTG_HS_DIEPINT5 + 0x1A8 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + MCNT + Multi count + 29 + 2 + + + + + OTG_HS_DTXFSTS7 + OTG_HS_DTXFSTS7 + OTG_HS device IN endpoint transmit FIFO + status register + 0x1AC + 32 + read-write + 0x0 + + + INEPTFSAV + IN endpoint TxFIFO space + avail + 0 + 16 + + + + + OTG_HS_DOEPCTL4 + OTG_HS_DOEPCTL4 + OTG device endpoint-4 control + register + 0x380 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL5 + OTG_HS_DOEPCTL5 + OTG device endpoint-5 control + register + 0x3A0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL6 + OTG_HS_DOEPCTL6 + OTG device endpoint-6 control + register + 0x3C0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPCTL7 + OTG_HS_DOEPCTL7 + OTG device endpoint-7 control + register + 0x3E0 + 32 + 0x0 + + + MPSIZ + Maximum packet size + 0 + 11 + read-write + + + USBAEP + USB active endpoint + 15 + 1 + read-write + + + EONUM_DPID + Even odd frame/Endpoint data + PID + 16 + 1 + read-only + + + NAKSTS + NAK status + 17 + 1 + read-only + + + EPTYP + Endpoint type + 18 + 2 + read-write + + + SNPM + Snoop mode + 20 + 1 + read-write + + + Stall + STALL handshake + 21 + 1 + read-write + + + CNAK + Clear NAK + 26 + 1 + write-only + + + SNAK + Set NAK + 27 + 1 + write-only + + + SD0PID_SEVNFRM + Set DATA0 PID/Set even + frame + 28 + 1 + write-only + + + SODDFRM + Set odd frame + 29 + 1 + write-only + + + EPDIS + Endpoint disable + 30 + 1 + read-write + + + EPENA + Endpoint enable + 31 + 1 + read-write + + + + + OTG_HS_DOEPTSIZ5 + OTG_HS_DOEPTSIZ5 + OTG_HS device endpoint-5 transfer size + register + 0x3B0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ6 + OTG_HS_DOEPTSIZ6 + OTG_HS device endpoint-6 transfer size + register + 0x3D0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + OTG_HS_DOEPTSIZ7 + OTG_HS_DOEPTSIZ7 + OTG_HS device endpoint-7 transfer size + register + 0x3F0 + 32 + read-write + 0x0 + + + XFRSIZ + Transfer size + 0 + 19 + + + PKTCNT + Packet count + 19 + 10 + + + RXDPID_STUPCNT + Received data PID/SETUP packet + count + 29 + 2 + + + + + + + OTG2_HS_DEVICE + 0x40080800 + + + OTG1_HS_PWRCLK + USB 1 on the go high speed + USB_OTG_HS + 0x40040E00 + + 0x0 + 0x3F200 + registers + + + + OTG_HS_PCGCR + OTG_HS_PCGCR + Power and clock gating control + register + 0x0 + 32 + read-write + 0x0 + + + STPPCLK + Stop PHY clock + 0 + 1 + + + GATEHCLK + Gate HCLK + 1 + 1 + + + PHYSUSP + PHY suspended + 4 + 1 + + + + + + + OTG2_HS_PWRCLK + 0x40080E00 + + + Ethernet_DMA + Ethernet: DMA mode register (DMA) + Ethernet + 0x40029000 + + 0x0 + 0x400 + registers + + + + DMAMR + DMAMR + DMA mode register + 0x0 + 0x20 + 0x00000000 + + + SWR + Software Reset + 0 + 1 + read-write + + + DA + DMA Tx or Rx Arbitration + Scheme + 1 + 1 + read-only + + + TXPR + Transmit priority + 11 + 1 + read-only + + + PR + Priority ratio + 12 + 3 + read-only + + + INTM + Interrupt Mode + 16 + 1 + read-write + + + + + DMASBMR + DMASBMR + System bus mode register + 0x04 + 0x20 + 0x01010000 + + + FB + Fixed Burst Length + 0 + 1 + read-write + + + AAL + Address-Aligned Beats + 12 + 1 + read-write + + + MB + Mixed Burst + 14 + 1 + read-only + + + RB + Rebuild INCRx Burst + 15 + 1 + read-only + + + + + DMAISR + DMAISR + Interrupt status register + 0x08 + 0x20 + read-only + 0x00000000 + + + DC0IS + DMA Channel Interrupt + Status + 0 + 1 + + + MTLIS + MTL Interrupt Status + 16 + 1 + + + MACIS + MAC Interrupt Status + 17 + 1 + + + + + DMADSR + DMADSR + Debug status register + 0x0C + 0x20 + read-only + 0x00000000 + + + AXWHSTS + AHB Master Write Channel + 0 + 1 + + + RPS0 + DMA Channel Receive Process + State + 8 + 4 + + + TPS0 + DMA Channel Transmit Process + State + 12 + 4 + + + + + DMACCR + DMACCR + Channel control register + 0x100 + 0x20 + read-write + 0x00000000 + + + MSS + Maximum Segment Size + 0 + 14 + + + PBLX8 + 8xPBL mode + 16 + 1 + + + DSL + Descriptor Skip Length + 18 + 3 + + + + + DMACTxCR + DMACTxCR + Channel transmit control + register + 0x104 + 0x20 + read-write + 0x00000000 + + + ST + Start or Stop Transmission + Command + 0 + 1 + + + OSF + Operate on Second Packet + 4 + 1 + + + TSE + TCP Segmentation Enabled + 12 + 1 + + + TXPBL + Transmit Programmable Burst + Length + 16 + 6 + + + + + DMACRxCR + DMACRxCR + Channel receive control + register + 0x108 + 0x20 + read-write + 0x00000000 + + + SR + Start or Stop Receive + Command + 0 + 1 + + + RBSZ + Receive Buffer size + 1 + 14 + + + RXPBL + RXPBL + 16 + 6 + + + RPF + DMA Rx Channel Packet + Flush + 31 + 1 + + + + + DMACTxDLAR + DMACTxDLAR + Channel Tx descriptor list address + register + 0x114 + 0x20 + read-write + 0x00000000 + + + TDESLA + Start of Transmit List + 2 + 30 + + + + + DMACRxDLAR + DMACRxDLAR + Channel Rx descriptor list address + register + 0x11C + 0x20 + read-write + 0x00000000 + + + RDESLA + Start of Receive List + 2 + 30 + + + + + DMACTxDTPR + DMACTxDTPR + Channel Tx descriptor tail pointer + register + 0x120 + 0x20 + read-write + 0x00000000 + + + TDT + Transmit Descriptor Tail + Pointer + 2 + 30 + + + + + DMACRxDTPR + DMACRxDTPR + Channel Rx descriptor tail pointer + register + 0x128 + 0x20 + read-write + 0x00000000 + + + RDT + Receive Descriptor Tail + Pointer + 2 + 30 + + + + + DMACTxRLR + DMACTxRLR + Channel Tx descriptor ring length + register + 0x12C + 0x20 + read-write + 0x00000000 + + + TDRL + Transmit Descriptor Ring + Length + 0 + 10 + + + + + DMACRxRLR + DMACRxRLR + Channel Rx descriptor ring length + register + 0x130 + 0x20 + read-write + 0x00000000 + + + RDRL + Receive Descriptor Ring + Length + 0 + 10 + + + + + DMACIER + DMACIER + Channel interrupt enable + register + 0x134 + 0x20 + read-write + 0x00000000 + + + TIE + Transmit Interrupt Enable + 0 + 1 + + + TXSE + Transmit Stopped Enable + 1 + 1 + + + TBUE + Transmit Buffer Unavailable + Enable + 2 + 1 + + + RIE + Receive Interrupt Enable + 6 + 1 + + + RBUE + Receive Buffer Unavailable + Enable + 7 + 1 + + + RSE + Receive Stopped Enable + 8 + 1 + + + RWTE + Receive Watchdog Timeout + Enable + 9 + 1 + + + ETIE + Early Transmit Interrupt + Enable + 10 + 1 + + + ERIE + Early Receive Interrupt + Enable + 11 + 1 + + + FBEE + Fatal Bus Error Enable + 12 + 1 + + + CDEE + Context Descriptor Error + Enable + 13 + 1 + + + AIE + Abnormal Interrupt Summary + Enable + 14 + 1 + + + NIE + Normal Interrupt Summary + Enable + 15 + 1 + + + + + DMACRxIWTR + DMACRxIWTR + Channel Rx interrupt watchdog timer + register + 0x138 + 0x20 + read-write + 0x00000000 + + + RWT + Receive Interrupt Watchdog Timer + Count + 0 + 8 + + + + + DMACCATxDR + DMACCATxDR + Channel current application transmit + descriptor register + 0x144 + 0x20 + read-only + 0x00000000 + + + CURTDESAPTR + Application Transmit Descriptor Address + Pointer + 0 + 32 + + + + + DMACCARxDR + DMACCARxDR + Channel current application receive + descriptor register + 0x14C + 0x20 + read-only + 0x00000000 + + + CURRDESAPTR + Application Receive Descriptor Address + Pointer + 0 + 32 + + + + + DMACCATxBR + DMACCATxBR + Channel current application transmit buffer + register + 0x154 + 0x20 + read-only + 0x00000000 + + + CURTBUFAPTR + Application Transmit Buffer Address + Pointer + 0 + 32 + + + + + DMACCARxBR + DMACCARxBR + Channel current application receive buffer + register + 0x15C + 0x20 + read-only + 0x00000000 + + + CURRBUFAPTR + Application Receive Buffer Address + Pointer + 0 + 32 + + + + + DMACSR + DMACSR + Channel status register + 0x160 + 0x20 + 0x00000000 + + + TI + Transmit Interrupt + 0 + 1 + read-write + + + TPS + Transmit Process Stopped + 1 + 1 + read-write + + + TBU + Transmit Buffer + Unavailable + 2 + 1 + read-write + + + RI + Receive Interrupt + 6 + 1 + read-write + + + RBU + Receive Buffer Unavailable + 7 + 1 + read-write + + + RPS + Receive Process Stopped + 8 + 1 + read-write + + + RWT + Receive Watchdog Timeout + 9 + 1 + read-write + + + ET + Early Transmit Interrupt + 10 + 1 + read-write + + + ER + Early Receive Interrupt + 11 + 1 + read-write + + + FBE + Fatal Bus Error + 12 + 1 + read-write + + + CDE + Context Descriptor Error + 13 + 1 + read-write + + + AIS + Abnormal Interrupt Summary + 14 + 1 + read-write + + + NIS + Normal Interrupt Summary + 15 + 1 + read-write + + + TEB + Tx DMA Error Bits + 16 + 3 + read-only + + + REB + Rx DMA Error Bits + 19 + 3 + read-only + + + + + DMACMFCR + DMACMFCR + Channel missed frame count + register + 0x16C + 0x20 + read-only + 0x00000000 + + + MFC + Dropped Packet Counters + 0 + 11 + + + MFCO + Overflow status of the MFC + Counter + 15 + 1 + + + + + + + Ethernet_MTL + Ethernet: MTL mode register (MTL) + Ethernet + 0x40028C00 + + 0x0 + 0x200 + registers + + + + MTLOMR + MTLOMR + Operating mode Register + 0x0 + 0x20 + read-write + 0x00000000 + + + DTXSTS + DTXSTS + 1 + 1 + + + CNTPRST + CNTPRST + 8 + 1 + + + CNTCLR + CNTCLR + 9 + 1 + + + + + MTLISR + MTLISR + Interrupt status Register + 0x20 + 0x20 + read-only + 0x00000000 + + + Q0IS + Queue interrupt status + 0 + 1 + + + + + MTLTxQOMR + MTLTxQOMR + Tx queue operating mode + Register + 0x100 + 0x20 + 0x00070008 + + + FTQ + Flush Transmit Queue + 0 + 1 + read-write + + + TSF + Transmit Store and Forward + 1 + 1 + read-write + + + TXQEN + Transmit Queue Enable + 2 + 2 + read-only + + + TTC + Transmit Threshold Control + 4 + 3 + read-write + + + TQS + Transmit Queue Size + 16 + 3 + read-write + + + + + MTLTxQUR + MTLTxQUR + Tx queue underflow register + 0x104 + 0x20 + read-only + 0x00000000 + + + UFFRMCNT + Underflow Packet Counter + 0 + 11 + + + UFCNTOVF + UFCNTOVF + 11 + 1 + + + + + MTLTxQDR + MTLTxQDR + Tx queue debug Register + 0x108 + 0x20 + read-only + 0x00000000 + + + TXQPAUSED + TXQPAUSED + 0 + 1 + + + TRCSTS + TRCSTS + 1 + 2 + + + TWCSTS + TWCSTS + 3 + 1 + + + TXQSTS + TXQSTS + 4 + 1 + + + TXSTSFSTS + TXSTSFSTS + 5 + 1 + + + PTXQ + PTXQ + 16 + 3 + + + STXSTSF + STXSTSF + 20 + 3 + + + + + MTLQICSR + MTLQICSR + Queue interrupt control status + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + TXUNFIS + TXUNFIS + 0 + 1 + + + TXUIE + TXUIE + 8 + 1 + + + RXOVFIS + RXOVFIS + 16 + 1 + + + RXOIE + RXOIE + 24 + 1 + + + + + MTLRxQOMR + MTLRxQOMR + Rx queue operating mode + register + 0x130 + 0x20 + 0x00700000 + + + RTC + RTC + 0 + 2 + read-write + + + FUP + FUP + 3 + 1 + read-write + + + FEP + FEP + 4 + 1 + read-write + + + RSF + RSF + 5 + 1 + read-write + + + DIS_TCP_EF + DIS_TCP_EF + 6 + 1 + read-write + + + EHFC + EHFC + 7 + 1 + read-write + + + RFA + RFA + 8 + 3 + read-write + + + RFD + RFD + 14 + 3 + read-write + + + RQS + RQS + 20 + 3 + read-only + + + + + MTLRxQMPOCR + MTLRxQMPOCR + Rx queue missed packet and overflow counter + register + 0x134 + 0x20 + read-only + 0x00000000 + + + OVFPKTCNT + OVFPKTCNT + 0 + 11 + + + OVFCNTOVF + OVFCNTOVF + 11 + 1 + + + MISPKTCNT + MISPKTCNT + 16 + 11 + + + MISCNTOVF + MISCNTOVF + 27 + 1 + + + + + MTLRxQDR + MTLRxQDR + Rx queue debug register + 0x138 + 0x20 + read-only + 0x00000000 + + + RWCSTS + RWCSTS + 0 + 1 + + + RRCSTS + RRCSTS + 1 + 2 + + + RXQSTS + RXQSTS + 4 + 2 + + + PRXQ + PRXQ + 16 + 14 + + + + + + + Ethernet_MAC + Ethernet: media access control (MAC) + Ethernet + 0x40028000 + + 0x0 + 0xBDF + registers + + + ETH + Ethernet global interrupt + 61 + + + + MACCR + MACCR + Operating mode configuration + register + 0x0 + 0x20 + read-write + 0x00000000 + + + RE + Receiver Enable + 0 + 1 + + + TE + TE + 1 + 1 + + + PRELEN + PRELEN + 2 + 2 + + + DC + DC + 4 + 1 + + + BL + BL + 5 + 2 + + + DR + DR + 8 + 1 + + + DCRS + DCRS + 9 + 1 + + + DO + DO + 10 + 1 + + + ECRSFD + ECRSFD + 11 + 1 + + + LM + LM + 12 + 1 + + + DM + DM + 13 + 1 + + + FES + FES + 14 + 1 + + + JE + JE + 16 + 1 + + + JD + JD + 17 + 1 + + + WD + WD + 19 + 1 + + + ACS + ACS + 20 + 1 + + + CST + CST + 21 + 1 + + + S2KP + S2KP + 22 + 1 + + + GPSLCE + GPSLCE + 23 + 1 + + + IPG + IPG + 24 + 3 + + + IPC + IPC + 27 + 1 + + + SARC + SARC + 28 + 3 + + + ARPEN + ARPEN + 31 + 1 + + + + + MACECR + MACECR + Extended operating mode configuration + register + 0x4 + 0x20 + read-write + 0x00000000 + + + GPSL + GPSL + 0 + 14 + + + DCRCC + DCRCC + 16 + 1 + + + SPEN + SPEN + 17 + 1 + + + USP + USP + 18 + 1 + + + EIPGEN + EIPGEN + 24 + 1 + + + EIPG + EIPG + 25 + 5 + + + + + MACPFR + MACPFR + Packet filtering control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + PR + PR + 0 + 1 + + + HUC + HUC + 1 + 1 + + + HMC + HMC + 2 + 1 + + + DAIF + DAIF + 3 + 1 + + + PM + PM + 4 + 1 + + + DBF + DBF + 5 + 1 + + + PCF + PCF + 6 + 2 + + + SAIF + SAIF + 8 + 1 + + + SAF + SAF + 9 + 1 + + + HPF + HPF + 10 + 1 + + + VTFE + VTFE + 16 + 1 + + + IPFE + IPFE + 20 + 1 + + + DNTU + DNTU + 21 + 1 + + + RA + RA + 31 + 1 + + + + + MACWTR + MACWTR + Watchdog timeout register + 0xC + 0x20 + read-write + 0x00000000 + + + WTO + WTO + 0 + 4 + + + PWE + PWE + 8 + 1 + + + + + MACHT0R + MACHT0R + Hash Table 0 register + 0x10 + 0x20 + read-write + 0x00000000 + + + HT31T0 + HT31T0 + 0 + 32 + + + + + MACHT1R + MACHT1R + Hash Table 1 register + 0x14 + 0x20 + read-write + 0x00000000 + + + HT63T32 + HT63T32 + 0 + 32 + + + + + MACVTR + MACVTR + VLAN tag register + 0x50 + 0x20 + read-write + 0x00000000 + + + VL + VL + 0 + 16 + + + ETV + ETV + 16 + 1 + + + VTIM + VTIM + 17 + 1 + + + ESVL + ESVL + 18 + 1 + + + ERSVLM + ERSVLM + 19 + 1 + + + DOVLTC + DOVLTC + 20 + 1 + + + EVLS + EVLS + 21 + 2 + + + EVLRXS + EVLRXS + 24 + 1 + + + VTHM + VTHM + 25 + 1 + + + EDVLP + EDVLP + 26 + 1 + + + ERIVLT + ERIVLT + 27 + 1 + + + EIVLS + EIVLS + 28 + 2 + + + EIVLRXS + EIVLRXS + 31 + 1 + + + + + MACVHTR + MACVHTR + VLAN Hash table register + 0x58 + 0x20 + read-write + 0x00000000 + + + VLHT + VLHT + 0 + 16 + + + + + MACVIR + MACVIR + VLAN inclusion register + 0x60 + 0x20 + read-write + 0x00000000 + + + VLT + VLT + 0 + 16 + + + VLC + VLC + 16 + 2 + + + VLP + VLP + 18 + 1 + + + CSVL + CSVL + 19 + 1 + + + VLTI + VLTI + 20 + 1 + + + + + MACIVIR + MACIVIR + Inner VLAN inclusion register + 0x64 + 0x20 + read-write + 0x00000000 + + + VLT + VLT + 0 + 16 + + + VLC + VLC + 16 + 2 + + + VLP + VLP + 18 + 1 + + + CSVL + CSVL + 19 + 1 + + + VLTI + VLTI + 20 + 1 + + + + + MACQTxFCR + MACQTxFCR + Tx Queue flow control register + 0x70 + 0x20 + read-write + 0x00000000 + + + FCB_BPA + FCB_BPA + 0 + 1 + + + TFE + TFE + 1 + 1 + + + PLT + PLT + 4 + 3 + + + DZPQ + DZPQ + 7 + 1 + + + PT + PT + 16 + 16 + + + + + MACRxFCR + MACRxFCR + Rx flow control register + 0x90 + 0x20 + read-write + 0x00000000 + + + RFE + RFE + 0 + 1 + + + UP + UP + 1 + 1 + + + + + MACISR + MACISR + Interrupt status register + 0xB0 + 0x20 + read-only + 0x00000000 + + + PHYIS + PHYIS + 3 + 1 + + + PMTIS + PMTIS + 4 + 1 + + + LPIIS + LPIIS + 5 + 1 + + + MMCIS + MMCIS + 8 + 1 + + + MMCRXIS + MMCRXIS + 9 + 1 + + + MMCTXIS + MMCTXIS + 10 + 1 + + + TSIS + TSIS + 12 + 1 + + + TXSTSIS + TXSTSIS + 13 + 1 + + + RXSTSIS + RXSTSIS + 14 + 1 + + + + + MACIER + MACIER + Interrupt enable register + 0xB4 + 0x20 + read-write + 0x00000000 + + + PHYIE + PHYIE + 3 + 1 + + + PMTIE + PMTIE + 4 + 1 + + + LPIIE + LPIIE + 5 + 1 + + + TSIE + TSIE + 12 + 1 + + + TXSTSIE + TXSTSIE + 13 + 1 + + + RXSTSIE + RXSTSIE + 14 + 1 + + + + + MACRxTxSR + MACRxTxSR + Rx Tx status register + 0xB8 + 0x20 + read-only + 0x00000000 + + + TJT + TJT + 0 + 1 + + + NCARR + NCARR + 1 + 1 + + + LCARR + LCARR + 2 + 1 + + + EXDEF + EXDEF + 3 + 1 + + + LCOL + LCOL + 4 + 1 + + + EXCOL + LCOL + 5 + 1 + + + RWT + RWT + 8 + 1 + + + + + MACPCSR + MACPCSR + PMT control status register + 0xC0 + 0x20 + 0x00000000 + + + PWRDWN + PWRDWN + 0 + 1 + read-write + + + MGKPKTEN + MGKPKTEN + 1 + 1 + read-write + + + RWKPKTEN + RWKPKTEN + 2 + 1 + read-write + + + MGKPRCVD + MGKPRCVD + 5 + 1 + read-only + + + RWKPRCVD + RWKPRCVD + 6 + 1 + read-only + + + GLBLUCAST + GLBLUCAST + 9 + 1 + read-write + + + RWKPFE + RWKPFE + 10 + 1 + read-write + + + RWKPTR + RWKPTR + 24 + 5 + read-write + + + RWKFILTRST + RWKFILTRST + 31 + 1 + read-write + + + + + MACRWKPFR + MACRWKPFR + Remove wakeup packet filter + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + MACRWKPFR + MACRWKPFR + 0 + 32 + + + + + MACLCSR + MACLCSR + LPI control status register + 0xD0 + 0x20 + 0x00000000 + + + TLPIEN + TLPIEN + 0 + 1 + read-only + + + TLPIEX + TLPIEX + 1 + 1 + read-only + + + RLPIEN + RLPIEN + 2 + 1 + read-only + + + RLPIEX + RLPIEX + 3 + 1 + read-only + + + TLPIST + TLPIST + 8 + 1 + read-only + + + RLPIST + RLPIST + 9 + 1 + read-only + + + LPIEN + LPIEN + 16 + 1 + read-write + + + PLS + PLS + 17 + 1 + read-write + + + PLSEN + PLSEN + 18 + 1 + read-write + + + LPITXA + LPITXA + 19 + 1 + read-write + + + LPITE + LPITE + 20 + 1 + read-write + + + + + MACLTCR + MACLTCR + LPI timers control register + 0xD4 + 0x20 + read-write + 0x03E80000 + + + TWT + TWT + 0 + 16 + + + LST + LST + 16 + 10 + + + + + MACLETR + MACLETR + LPI entry timer register + 0xD8 + 0x20 + read-write + 0x00000000 + + + LPIET + LPIET + 0 + 17 + + + + + MAC1USTCR + MAC1USTCR + 1-microsecond-tick counter + register + 0xDC + 0x20 + read-write + 0x00000000 + + + TIC_1US_CNTR + TIC_1US_CNTR + 0 + 12 + + + + + MACVR + MACVR + Version register + 0x110 + 0x20 + read-only + 0x00003041 + + + SNPSVER + SNPSVER + 0 + 8 + + + USERVER + USERVER + 8 + 8 + + + + + MACDR + MACDR + Debug register + 0x114 + 0x20 + read-only + 0x00000000 + + + RPESTS + RPESTS + 0 + 1 + + + RFCFCSTS + RFCFCSTS + 1 + 2 + + + TPESTS + TPESTS + 16 + 1 + + + TFCSTS + TFCSTS + 17 + 2 + + + + + MACHWF1R + MACHWF1R + HW feature 1 register + 0x120 + 0x20 + read-only + 0x11841904 + + + RXFIFOSIZE + RXFIFOSIZE + 0 + 5 + + + TXFIFOSIZE + TXFIFOSIZE + 6 + 5 + + + OSTEN + OSTEN + 11 + 1 + + + PTOEN + PTOEN + 12 + 1 + + + ADVTHWORD + ADVTHWORD + 13 + 1 + + + ADDR64 + ADDR64 + 14 + 2 + + + DCBEN + DCBEN + 16 + 1 + + + SPHEN + SPHEN + 17 + 1 + + + TSOEN + TSOEN + 18 + 1 + + + DBGMEMA + DBGMEMA + 19 + 1 + + + AVSEL + AVSEL + 20 + 1 + + + HASHTBLSZ + HASHTBLSZ + 24 + 2 + + + L3L4FNUM + L3L4FNUM + 27 + 4 + + + + + MACHWF2R + MACHWF2R + HW feature 2 register + 0x124 + 0x20 + read-only + 0x41000000 + + + RXQCNT + RXQCNT + 0 + 4 + + + TXQCNT + TXQCNT + 6 + 4 + + + RXCHCNT + RXCHCNT + 12 + 4 + + + TXCHCNT + TXCHCNT + 18 + 4 + + + PPSOUTNUM + PPSOUTNUM + 24 + 3 + + + AUXSNAPNUM + AUXSNAPNUM + 28 + 3 + + + + + MACMDIOAR + MACMDIOAR + MDIO address register + 0x200 + 0x20 + read-write + 0x00000000 + + + MB + MB + 0 + 1 + + + C45E + C45E + 1 + 1 + + + GOC + GOC + 2 + 2 + + + SKAP + SKAP + 4 + 1 + + + CR + CR + 8 + 4 + + + NTC + NTC + 12 + 3 + + + RDA + RDA + 16 + 5 + + + PA + PA + 21 + 5 + + + BTB + BTB + 26 + 1 + + + PSE + PSE + 27 + 1 + + + + + MACMDIODR + MACMDIODR + MDIO data register + 0x204 + 0x20 + read-write + 0x00000000 + + + MD + MD + 0 + 16 + + + RA + RA + 16 + 16 + + + + + MACARPAR + MACARPAR + ARP address register + 0xAE0 + 0x20 + read-write + 0x00000000 + + + ARPPA + ARPPA + 0 + 32 + + + + + MACA0HR + MACA0HR + Address 0 high register + 0x300 + 0x20 + 0x8000FFFF + + + ADDRHI + ADDRHI + 0 + 16 + read-write + + + AE + AE + 31 + 1 + read-only + + + + + MACA0LR + MACA0LR + Address 0 low register + 0x304 + 0x20 + read-write + 0xFFFFFFFF + + + ADDRLO + ADDRLO + 0 + 32 + + + + + MACA1LR + MACA1LR + Address 1 low register + 0x30C + 0x20 + read-write + 0xFFFFFFFF + + + ADDRLO + ADDRLO + 0 + 32 + + + + + MACA2LR + MACA2LR + Address 2 low register + 0x314 + 0x20 + read-write + 0xFFFFFFFF + + + ADDRLO + ADDRLO + 0 + 32 + + + + + MACA1HR + MACA1HR + Address 1 high register + 0x308 + 0x20 + read-write + 0x0000FFFF + + + ADDRHI + ADDRHI + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA2HR + MACA2HR + Address 2 high register + 0x310 + 0x20 + read-write + 0x0000FFFF + + + ADDRHI + ADDRHI + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3HR + MACA3HR + Address 3 high register + 0x318 + 0x20 + read-write + 0x0000FFFF + + + ADDRHI + ADDRHI + 0 + 16 + + + MBC + MBC + 24 + 6 + + + SA + SA + 30 + 1 + + + AE + AE + 31 + 1 + + + + + MACA3LR + MACA3LR + Address 3 low register + 0x31C + 0x20 + read-write + 0xFFFFFFFF + + + ADDRLO + ADDRLO + 0 + 32 + + + + + MMC_CONTROL + MMC_CONTROL + MMC control register + 0x700 + 0x20 + read-write + 0x00000000 + + + CNTRST + CNTRST + 0 + 1 + + + CNTSTOPRO + CNTSTOPRO + 1 + 1 + + + RSTONRD + RSTONRD + 2 + 1 + + + CNTFREEZ + CNTFREEZ + 3 + 1 + + + CNTPRST + CNTPRST + 4 + 1 + + + CNTPRSTLVL + CNTPRSTLVL + 5 + 1 + + + UCDBC + UCDBC + 8 + 1 + + + + + MMC_RX_INTERRUPT + MMC_RX_INTERRUPT + MMC Rx interrupt register + 0x704 + 0x20 + read-only + 0x00000000 + + + RXCRCERPIS + RXCRCERPIS + 5 + 1 + + + RXALGNERPIS + RXALGNERPIS + 6 + 1 + + + RXUCGPIS + RXUCGPIS + 17 + 1 + + + RXLPIUSCIS + RXLPIUSCIS + 26 + 1 + + + RXLPITRCIS + RXLPITRCIS + 27 + 1 + + + + + MMC_TX_INTERRUPT + MMC_TX_INTERRUPT + MMC Tx interrupt register + 0x708 + 0x20 + read-only + 0x00000000 + + + TXSCOLGPIS + TXSCOLGPIS + 14 + 1 + + + TXMCOLGPIS + TXMCOLGPIS + 15 + 1 + + + TXGPKTIS + TXGPKTIS + 21 + 1 + + + TXLPIUSCIS + TXLPIUSCIS + 26 + 1 + + + TXLPITRCIS + TXLPITRCIS + 27 + 1 + + + + + MMC_RX_INTERRUPT_MASK + MMC_RX_INTERRUPT_MASK + MMC Rx interrupt mask register + 0x70C + 0x20 + 0x00000000 + + + RXCRCERPIM + RXCRCERPIM + 5 + 1 + read-write + + + RXALGNERPIM + RXALGNERPIM + 6 + 1 + read-write + + + RXUCGPIM + RXUCGPIM + 17 + 1 + read-write + + + RXLPIUSCIM + RXLPIUSCIM + 26 + 1 + read-write + + + RXLPITRCIM + RXLPITRCIM + 27 + 1 + read-only + + + + + MMC_TX_INTERRUPT_MASK + MMC_TX_INTERRUPT_MASK + MMC Tx interrupt mask register + 0x710 + 0x20 + 0x00000000 + + + TXSCOLGPIM + TXSCOLGPIM + 14 + 1 + read-write + + + TXMCOLGPIM + TXMCOLGPIM + 15 + 1 + read-write + + + TXGPKTIM + TXGPKTIM + 21 + 1 + read-write + + + TXLPIUSCIM + TXLPIUSCIM + 26 + 1 + read-write + + + TXLPITRCIM + TXLPITRCIM + 27 + 1 + read-only + + + + + TX_SINGLE_COLLISION_GOOD_PACKETS + + TX_SINGLE_COLLISION_GOOD_PACKETS + Tx single collision good packets + register + 0x74C + 0x20 + read-only + 0x00000000 + + + TXSNGLCOLG + TXSNGLCOLG + 0 + 32 + + + + + TX_MULTIPLE_COLLISION_GOOD_PACKETS + + TX_MULTIPLE_COLLISION_GOOD_PACKETS + Tx multiple collision good packets + register + 0x750 + 0x20 + read-only + 0x00000000 + + + TXMULTCOLG + TXMULTCOLG + 0 + 32 + + + + + TX_PACKET_COUNT_GOOD + TX_PACKET_COUNT_GOOD + Tx packet count good register + 0x768 + 0x20 + read-only + 0x00000000 + + + TXPKTG + TXPKTG + 0 + 32 + + + + + RX_CRC_ERROR_PACKETS + RX_CRC_ERROR_PACKETS + Rx CRC error packets register + 0x794 + 0x20 + read-only + 0x00000000 + + + RXCRCERR + RXCRCERR + 0 + 32 + + + + + RX_ALIGNMENT_ERROR_PACKETS + RX_ALIGNMENT_ERROR_PACKETS + Rx alignment error packets + register + 0x798 + 0x20 + read-only + 0x00000000 + + + RXALGNERR + RXALGNERR + 0 + 32 + + + + + RX_UNICAST_PACKETS_GOOD + RX_UNICAST_PACKETS_GOOD + Rx unicast packets good + register + 0x7C4 + 0x20 + read-only + 0x00000000 + + + RXUCASTG + RXUCASTG + 0 + 32 + + + + + TX_LPI_USEC_CNTR + TX_LPI_USEC_CNTR + Tx LPI microsecond timer + register + 0x7EC + 0x20 + read-only + 0x00000000 + + + TXLPIUSC + TXLPIUSC + 0 + 32 + + + + + TX_LPI_TRAN_CNTR + TX_LPI_TRAN_CNTR + Tx LPI transition counter + register + 0x7F0 + 0x20 + read-only + 0x00000000 + + + TXLPITRC + TXLPITRC + 0 + 32 + + + + + RX_LPI_USEC_CNTR + RX_LPI_USEC_CNTR + Rx LPI microsecond counter + register + 0x7F4 + 0x20 + read-only + 0x00000000 + + + RXLPIUSC + RXLPIUSC + 0 + 32 + + + + + RX_LPI_TRAN_CNTR + RX_LPI_TRAN_CNTR + Rx LPI transition counter + register + 0x7F8 + 0x20 + read-only + 0x00000000 + + + RXLPITRC + RXLPITRC + 0 + 32 + + + + + MACL3L4C0R + MACL3L4C0R + L3 and L4 control 0 register + 0x900 + 0x20 + read-write + 0x00000000 + + + L3PEN0 + L3PEN0 + 0 + 1 + + + L3SAM0 + L3SAM0 + 2 + 1 + + + L3SAIM0 + L3SAIM0 + 3 + 1 + + + L3DAM0 + L3DAM0 + 4 + 1 + + + L3DAIM0 + L3DAIM0 + 5 + 1 + + + L3HSBM0 + L3HSBM0 + 6 + 5 + + + L3HDBM0 + L3HDBM0 + 11 + 5 + + + L4PEN0 + L4PEN0 + 16 + 1 + + + L4SPM0 + L4SPM0 + 18 + 1 + + + L4SPIM0 + L4SPIM0 + 19 + 1 + + + L4DPM0 + L4DPM0 + 20 + 1 + + + L4DPIM0 + L4DPIM0 + 21 + 1 + + + + + MACL4A0R + MACL4A0R + Layer4 address filter 0 + register + 0x904 + 0x20 + read-write + 0x00000000 + + + L4SP0 + L4SP0 + 0 + 16 + + + L4DP0 + L4DP0 + 16 + 16 + + + + + MACL3A00R + MACL3A00R + MACL3A00R + 0x910 + 0x20 + read-write + 0x00000000 + + + L3A00 + L3A00 + 0 + 32 + + + + + MACL3A10R + MACL3A10R + Layer3 address 1 filter 0 + register + 0x914 + 0x20 + read-write + 0x00000000 + + + L3A10 + L3A10 + 0 + 32 + + + + + MACL3A20 + MACL3A20 + Layer3 Address 2 filter 0 + register + 0x918 + 0x20 + read-write + 0x00000000 + + + L3A20 + L3A20 + 0 + 32 + + + + + MACL3A30 + MACL3A30 + Layer3 Address 3 filter 0 + register + 0x91C + 0x20 + read-write + 0x00000000 + + + L3A30 + L3A30 + 0 + 32 + + + + + MACL3L4C1R + MACL3L4C1R + L3 and L4 control 1 register + 0x930 + 0x20 + read-write + 0x00000000 + + + L3PEN1 + L3PEN1 + 0 + 1 + + + L3SAM1 + L3SAM1 + 2 + 1 + + + L3SAIM1 + L3SAIM1 + 3 + 1 + + + L3DAM1 + L3DAM1 + 4 + 1 + + + L3DAIM1 + L3DAIM1 + 5 + 1 + + + L3HSBM1 + L3HSBM1 + 6 + 5 + + + L3HDBM1 + L3HDBM1 + 11 + 5 + + + L4PEN1 + L4PEN1 + 16 + 1 + + + L4SPM1 + L4SPM1 + 18 + 1 + + + L4SPIM1 + L4SPIM1 + 19 + 1 + + + L4DPM1 + L4DPM1 + 20 + 1 + + + L4DPIM1 + L4DPIM1 + 21 + 1 + + + + + MACL4A1R + MACL4A1R + Layer 4 address filter 1 + register + 0x934 + 0x20 + read-write + 0x00000000 + + + L4SP1 + L4SP1 + 0 + 16 + + + L4DP1 + L4DP1 + 16 + 16 + + + + + MACL3A01R + MACL3A01R + Layer3 address 0 filter 1 + Register + 0x940 + 0x20 + read-write + 0x00000000 + + + L3A01 + L3A01 + 0 + 32 + + + + + MACL3A11R + MACL3A11R + Layer3 address 1 filter 1 + register + 0x944 + 0x20 + read-write + 0x00000000 + + + L3A11 + L3A11 + 0 + 32 + + + + + MACL3A21R + MACL3A21R + Layer3 address 2 filter 1 + Register + 0x948 + 0x20 + read-write + 0x00000000 + + + L3A21 + L3A21 + 0 + 32 + + + + + MACL3A31R + MACL3A31R + Layer3 address 3 filter 1 + register + 0x94C + 0x20 + read-write + 0x00000000 + + + L3A31 + L3A31 + 0 + 32 + + + + + MACTSCR + MACTSCR + Timestamp control Register + 0xB00 + 0x20 + 0x00000200 + + + TSENA + TSENA + 0 + 1 + read-write + + + TSCFUPDT + TSCFUPDT + 1 + 1 + read-write + + + TSINIT + TSINIT + 2 + 1 + read-write + + + TSUPDT + TSUPDT + 3 + 1 + read-write + + + TSADDREG + TSADDREG + 5 + 1 + read-write + + + TSENALL + TSENALL + 8 + 1 + read-write + + + TSCTRLSSR + TSCTRLSSR + 9 + 1 + read-write + + + TSVER2ENA + TSVER2ENA + 10 + 1 + read-write + + + TSIPENA + TSIPENA + 11 + 1 + read-write + + + TSIPV6ENA + TSIPV6ENA + 12 + 1 + read-write + + + TSIPV4ENA + TSIPV4ENA + 13 + 1 + read-write + + + TSEVNTENA + TSEVNTENA + 14 + 1 + read-write + + + TSMSTRENA + TSMSTRENA + 15 + 1 + read-write + + + SNAPTYPSEL + SNAPTYPSEL + 16 + 2 + read-write + + + TSENMACADDR + TSENMACADDR + 18 + 1 + read-write + + + CSC + CSC + 19 + 1 + read-only + + + TXTSSTSM + TXTSSTSM + 24 + 1 + read-write + + + + + MACSSIR + MACSSIR + Sub-second increment register + 0xB04 + 0x20 + read-write + 0x00000000 + + + SNSINC + SNSINC + 8 + 8 + + + SSINC + SSINC + 16 + 8 + + + + + MACSTSR + MACSTSR + System time seconds register + 0xB08 + 0x20 + read-only + 0x00000000 + + + TSS + TSS + 0 + 32 + + + + + MACSTNR + MACSTNR + System time nanoseconds + register + 0xB0C + 0x20 + read-only + 0x00000000 + + + TSSS + TSSS + 0 + 31 + + + + + MACSTSUR + MACSTSUR + System time seconds update + register + 0xB10 + 0x20 + read-write + 0x00000000 + + + TSS + TSS + 0 + 32 + + + + + MACSTNUR + MACSTNUR + System time nanoseconds update + register + 0xB14 + 0x20 + read-write + 0x00000000 + + + TSSS + TSSS + 0 + 31 + + + ADDSUB + ADDSUB + 31 + 1 + + + + + MACTSAR + MACTSAR + Timestamp addend register + 0xB18 + 0x20 + read-write + 0x00000000 + + + TSAR + TSAR + 0 + 32 + + + + + MACTSSR + MACTSSR + Timestamp status register + 0xB20 + 0x20 + read-only + 0x00000000 + + + TSSOVF + TSSOVF + 0 + 1 + + + TSTARGT0 + TSTARGT0 + 1 + 1 + + + AUXTSTRIG + AUXTSTRIG + 2 + 1 + + + TSTRGTERR0 + TSTRGTERR0 + 3 + 1 + + + TXTSSIS + TXTSSIS + 15 + 1 + + + ATSSTN + ATSSTN + 16 + 4 + + + ATSSTM + ATSSTM + 24 + 1 + + + ATSNS + ATSNS + 25 + 5 + + + + + MACTxTSSNR + MACTxTSSNR + Tx timestamp status nanoseconds + register + 0xB30 + 0x20 + read-only + 0x00000000 + + + TXTSSLO + TXTSSLO + 0 + 31 + + + TXTSSMIS + TXTSSMIS + 31 + 1 + + + + + MACTxTSSSR + MACTxTSSSR + Tx timestamp status seconds + register + 0xB34 + 0x20 + read-only + 0x00000000 + + + TXTSSHI + TXTSSHI + 0 + 32 + + + + + MACACR + MACACR + Auxiliary control register + 0xB40 + 0x20 + read-write + 0x00000000 + + + ATSFC + ATSFC + 0 + 1 + + + ATSEN0 + ATSEN0 + 4 + 1 + + + ATSEN1 + ATSEN1 + 5 + 1 + + + ATSEN2 + ATSEN2 + 6 + 1 + + + ATSEN3 + ATSEN3 + 7 + 1 + + + + + MACATSNR + MACATSNR + Auxiliary timestamp nanoseconds + register + 0xB48 + 0x20 + read-only + 0x00000000 + + + AUXTSLO + AUXTSLO + 0 + 31 + + + + + MACATSSR + MACATSSR + Auxiliary timestamp seconds + register + 0xB4C + 0x20 + read-only + 0x00000000 + + + AUXTSHI + AUXTSHI + 0 + 32 + + + + + MACTSIACR + MACTSIACR + Timestamp Ingress asymmetric correction + register + 0xB50 + 0x20 + read-write + 0x00000000 + + + OSTIAC + OSTIAC + 0 + 32 + + + + + MACTSEACR + MACTSEACR + Timestamp Egress asymmetric correction + register + 0xB54 + 0x20 + read-write + 0x00000000 + + + OSTEAC + OSTEAC + 0 + 32 + + + + + MACTSICNR + MACTSICNR + Timestamp Ingress correction nanosecond + register + 0xB58 + 0x20 + read-write + 0x00000000 + + + TSIC + TSIC + 0 + 32 + + + + + MACTSECNR + MACTSECNR + Timestamp Egress correction nanosecond + register + 0xB5C + 0x20 + read-write + 0x00000000 + + + TSEC + TSEC + 0 + 32 + + + + + MACPPSCR + MACPPSCR + PPS control register + 0xB70 + 0x20 + read-write + 0x00000000 + + + PPSCTRL + PPSCTRL + 0 + 4 + + + PPSEN0 + PPSEN0 + 4 + 1 + + + TRGTMODSEL0 + TRGTMODSEL0 + 5 + 2 + + + + + MACPPSTTSR + MACPPSTTSR + PPS target time seconds + register + 0xB80 + 0x20 + read-write + 0x00000000 + + + TSTRH0 + TSTRH0 + 0 + 31 + + + + + MACPPSTTNR + MACPPSTTNR + PPS target time nanoseconds + register + 0xB84 + 0x20 + read-write + 0x00000000 + + + TTSL0 + TTSL0 + 0 + 31 + + + TRGTBUSY0 + TRGTBUSY0 + 31 + 1 + + + + + MACPPSIR + MACPPSIR + PPS interval register + 0xB88 + 0x20 + read-write + 0x00000000 + + + PPSINT0 + PPSINT0 + 0 + 32 + + + + + MACPPSWR + MACPPSWR + PPS width register + 0xB8C + 0x20 + read-write + 0x00000000 + + + PPSWIDTH0 + PPSWIDTH0 + 0 + 32 + + + + + MACPOCR + MACPOCR + PTP Offload control register + 0xBC0 + 0x20 + read-write + 0x00000000 + + + PTOEN + PTOEN + 0 + 1 + + + ASYNCEN + ASYNCEN + 1 + 1 + + + APDREQEN + APDREQEN + 2 + 1 + + + ASYNCTRIG + ASYNCTRIG + 4 + 1 + + + APDREQTRIG + APDREQTRIG + 5 + 1 + + + DRRDIS + DRRDIS + 6 + 1 + + + DN + DN + 8 + 8 + + + + + MACSPI0R + MACSPI0R + PTP Source Port Identity 0 + Register + 0xBC4 + 0x20 + read-write + 0x00000000 + + + SPI0 + SPI0 + 0 + 32 + + + + + MACSPI1R + MACSPI1R + PTP Source port identity 1 + register + 0xBC8 + 0x20 + read-write + 0x00000000 + + + SPI1 + SPI1 + 0 + 32 + + + + + MACSPI2R + MACSPI2R + PTP Source port identity 2 + register + 0xBCC + 0x20 + read-write + 0x00000000 + + + SPI2 + SPI2 + 0 + 16 + + + + + MACLMIR + MACLMIR + Log message interval register + 0xBD0 + 0x20 + read-write + 0x00000000 + + + LSI + LSI + 0 + 8 + + + DRSYNCR + DRSYNCR + 8 + 3 + + + LMPDRI + LMPDRI + 24 + 8 + + + + + + + DMA1 + DMA controller + DMA + 0x40020000 + + 0x0 + 0x400 + registers + + + DMA_STR0 + DMA1 Stream0 + 11 + + + DMA_STR1 + DMA1 Stream1 + 12 + + + DMA1_STR7 + DMA1 Stream7 + 47 + + + + LISR + LISR + low interrupt status register + 0x0 + 0x20 + read-only + 0x00000000 + + + TCIF3 + Stream x transfer complete interrupt + flag (x = 3..0) + 27 + 1 + + + HTIF3 + Stream x half transfer interrupt flag + (x=3..0) + 26 + 1 + + + TEIF3 + Stream x transfer error interrupt flag + (x=3..0) + 25 + 1 + + + DMEIF3 + Stream x direct mode error interrupt + flag (x=3..0) + 24 + 1 + + + FEIF3 + Stream x FIFO error interrupt flag + (x=3..0) + 22 + 1 + + + TCIF2 + Stream x transfer complete interrupt + flag (x = 3..0) + 21 + 1 + + + HTIF2 + Stream x half transfer interrupt flag + (x=3..0) + 20 + 1 + + + TEIF2 + Stream x transfer error interrupt flag + (x=3..0) + 19 + 1 + + + DMEIF2 + Stream x direct mode error interrupt + flag (x=3..0) + 18 + 1 + + + FEIF2 + Stream x FIFO error interrupt flag + (x=3..0) + 16 + 1 + + + TCIF1 + Stream x transfer complete interrupt + flag (x = 3..0) + 11 + 1 + + + HTIF1 + Stream x half transfer interrupt flag + (x=3..0) + 10 + 1 + + + TEIF1 + Stream x transfer error interrupt flag + (x=3..0) + 9 + 1 + + + DMEIF1 + Stream x direct mode error interrupt + flag (x=3..0) + 8 + 1 + + + FEIF1 + Stream x FIFO error interrupt flag + (x=3..0) + 6 + 1 + + + TCIF0 + Stream x transfer complete interrupt + flag (x = 3..0) + 5 + 1 + + + HTIF0 + Stream x half transfer interrupt flag + (x=3..0) + 4 + 1 + + + TEIF0 + Stream x transfer error interrupt flag + (x=3..0) + 3 + 1 + + + DMEIF0 + Stream x direct mode error interrupt + flag (x=3..0) + 2 + 1 + + + FEIF0 + Stream x FIFO error interrupt flag + (x=3..0) + 0 + 1 + + + + + HISR + HISR + high interrupt status register + 0x4 + 0x20 + read-only + 0x00000000 + + + TCIF7 + Stream x transfer complete interrupt + flag (x=7..4) + 27 + 1 + + + HTIF7 + Stream x half transfer interrupt flag + (x=7..4) + 26 + 1 + + + TEIF7 + Stream x transfer error interrupt flag + (x=7..4) + 25 + 1 + + + DMEIF7 + Stream x direct mode error interrupt + flag (x=7..4) + 24 + 1 + + + FEIF7 + Stream x FIFO error interrupt flag + (x=7..4) + 22 + 1 + + + TCIF6 + Stream x transfer complete interrupt + flag (x=7..4) + 21 + 1 + + + HTIF6 + Stream x half transfer interrupt flag + (x=7..4) + 20 + 1 + + + TEIF6 + Stream x transfer error interrupt flag + (x=7..4) + 19 + 1 + + + DMEIF6 + Stream x direct mode error interrupt + flag (x=7..4) + 18 + 1 + + + FEIF6 + Stream x FIFO error interrupt flag + (x=7..4) + 16 + 1 + + + TCIF5 + Stream x transfer complete interrupt + flag (x=7..4) + 11 + 1 + + + HTIF5 + Stream x half transfer interrupt flag + (x=7..4) + 10 + 1 + + + TEIF5 + Stream x transfer error interrupt flag + (x=7..4) + 9 + 1 + + + DMEIF5 + Stream x direct mode error interrupt + flag (x=7..4) + 8 + 1 + + + FEIF5 + Stream x FIFO error interrupt flag + (x=7..4) + 6 + 1 + + + TCIF4 + Stream x transfer complete interrupt + flag (x=7..4) + 5 + 1 + + + HTIF4 + Stream x half transfer interrupt flag + (x=7..4) + 4 + 1 + + + TEIF4 + Stream x transfer error interrupt flag + (x=7..4) + 3 + 1 + + + DMEIF4 + Stream x direct mode error interrupt + flag (x=7..4) + 2 + 1 + + + FEIF4 + Stream x FIFO error interrupt flag + (x=7..4) + 0 + 1 + + + + + LIFCR + LIFCR + low interrupt flag clear + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CTCIF3 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 27 + 1 + + + CHTIF3 + Stream x clear half transfer interrupt + flag (x = 3..0) + 26 + 1 + + + CTEIF3 + Stream x clear transfer error interrupt + flag (x = 3..0) + 25 + 1 + + + CDMEIF3 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 24 + 1 + + + CFEIF3 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 22 + 1 + + + CTCIF2 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 21 + 1 + + + CHTIF2 + Stream x clear half transfer interrupt + flag (x = 3..0) + 20 + 1 + + + CTEIF2 + Stream x clear transfer error interrupt + flag (x = 3..0) + 19 + 1 + + + CDMEIF2 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 18 + 1 + + + CFEIF2 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 16 + 1 + + + CTCIF1 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 11 + 1 + + + CHTIF1 + Stream x clear half transfer interrupt + flag (x = 3..0) + 10 + 1 + + + CTEIF1 + Stream x clear transfer error interrupt + flag (x = 3..0) + 9 + 1 + + + CDMEIF1 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 8 + 1 + + + CFEIF1 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 6 + 1 + + + CTCIF0 + Stream x clear transfer complete + interrupt flag (x = 3..0) + 5 + 1 + + + CHTIF0 + Stream x clear half transfer interrupt + flag (x = 3..0) + 4 + 1 + + + CTEIF0 + Stream x clear transfer error interrupt + flag (x = 3..0) + 3 + 1 + + + CDMEIF0 + Stream x clear direct mode error + interrupt flag (x = 3..0) + 2 + 1 + + + CFEIF0 + Stream x clear FIFO error interrupt flag + (x = 3..0) + 0 + 1 + + + + + HIFCR + HIFCR + high interrupt flag clear + register + 0xC + 0x20 + read-write + 0x00000000 + + + CTCIF7 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 27 + 1 + + + CHTIF7 + Stream x clear half transfer interrupt + flag (x = 7..4) + 26 + 1 + + + CTEIF7 + Stream x clear transfer error interrupt + flag (x = 7..4) + 25 + 1 + + + CDMEIF7 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 24 + 1 + + + CFEIF7 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 22 + 1 + + + CTCIF6 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 21 + 1 + + + CHTIF6 + Stream x clear half transfer interrupt + flag (x = 7..4) + 20 + 1 + + + CTEIF6 + Stream x clear transfer error interrupt + flag (x = 7..4) + 19 + 1 + + + CDMEIF6 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 18 + 1 + + + CFEIF6 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 16 + 1 + + + CTCIF5 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 11 + 1 + + + CHTIF5 + Stream x clear half transfer interrupt + flag (x = 7..4) + 10 + 1 + + + CTEIF5 + Stream x clear transfer error interrupt + flag (x = 7..4) + 9 + 1 + + + CDMEIF5 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 8 + 1 + + + CFEIF5 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 6 + 1 + + + CTCIF4 + Stream x clear transfer complete + interrupt flag (x = 7..4) + 5 + 1 + + + CHTIF4 + Stream x clear half transfer interrupt + flag (x = 7..4) + 4 + 1 + + + CTEIF4 + Stream x clear transfer error interrupt + flag (x = 7..4) + 3 + 1 + + + CDMEIF4 + Stream x clear direct mode error + interrupt flag (x = 7..4) + 2 + 1 + + + CFEIF4 + Stream x clear FIFO error interrupt flag + (x = 7..4) + 0 + 1 + + + + + S0CR + S0CR + stream x configuration + register + 0x10 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S0NDTR + S0NDTR + stream x number of data + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S0PAR + S0PAR + stream x peripheral address + register + 0x18 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S0M0AR + S0M0AR + stream x memory 0 address + register + 0x1C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S0M1AR + S0M1AR + stream x memory 1 address + register + 0x20 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S0FCR + S0FCR + stream x FIFO control register + 0x24 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S1CR + S1CR + stream x configuration + register + 0x28 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S1NDTR + S1NDTR + stream x number of data + register + 0x2C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S1PAR + S1PAR + stream x peripheral address + register + 0x30 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S1M0AR + S1M0AR + stream x memory 0 address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S1M1AR + S1M1AR + stream x memory 1 address + register + 0x38 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S1FCR + S1FCR + stream x FIFO control register + 0x3C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S2CR + S2CR + stream x configuration + register + 0x40 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S2NDTR + S2NDTR + stream x number of data + register + 0x44 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S2PAR + S2PAR + stream x peripheral address + register + 0x48 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S2M0AR + S2M0AR + stream x memory 0 address + register + 0x4C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S2M1AR + S2M1AR + stream x memory 1 address + register + 0x50 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S2FCR + S2FCR + stream x FIFO control register + 0x54 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S3CR + S3CR + stream x configuration + register + 0x58 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S3NDTR + S3NDTR + stream x number of data + register + 0x5C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S3PAR + S3PAR + stream x peripheral address + register + 0x60 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S3M0AR + S3M0AR + stream x memory 0 address + register + 0x64 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S3M1AR + S3M1AR + stream x memory 1 address + register + 0x68 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S3FCR + S3FCR + stream x FIFO control register + 0x6C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S4CR + S4CR + stream x configuration + register + 0x70 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S4NDTR + S4NDTR + stream x number of data + register + 0x74 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S4PAR + S4PAR + stream x peripheral address + register + 0x78 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S4M0AR + S4M0AR + stream x memory 0 address + register + 0x7C + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S4M1AR + S4M1AR + stream x memory 1 address + register + 0x80 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S4FCR + S4FCR + stream x FIFO control register + 0x84 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S5CR + S5CR + stream x configuration + register + 0x88 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S5NDTR + S5NDTR + stream x number of data + register + 0x8C + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S5PAR + S5PAR + stream x peripheral address + register + 0x90 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S5M0AR + S5M0AR + stream x memory 0 address + register + 0x94 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S5M1AR + S5M1AR + stream x memory 1 address + register + 0x98 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S5FCR + S5FCR + stream x FIFO control register + 0x9C + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S6CR + S6CR + stream x configuration + register + 0xA0 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S6NDTR + S6NDTR + stream x number of data + register + 0xA4 + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S6PAR + S6PAR + stream x peripheral address + register + 0xA8 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S6M0AR + S6M0AR + stream x memory 0 address + register + 0xAC + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S6M1AR + S6M1AR + stream x memory 1 address + register + 0xB0 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S6FCR + S6FCR + stream x FIFO control register + 0xB4 + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + S7CR + S7CR + stream x configuration + register + 0xB8 + 0x20 + read-write + 0x00000000 + + + MBURST + Memory burst transfer + configuration + 23 + 2 + + + PBURST + Peripheral burst transfer + configuration + 21 + 2 + + + ACK + ACK + 20 + 1 + + + CT + Current target (only in double buffer + mode) + 19 + 1 + + + DBM + Double buffer mode + 18 + 1 + + + PL + Priority level + 16 + 2 + + + PINCOS + Peripheral increment offset + size + 15 + 1 + + + MSIZE + Memory data size + 13 + 2 + + + PSIZE + Peripheral data size + 11 + 2 + + + MINC + Memory increment mode + 10 + 1 + + + PINC + Peripheral increment mode + 9 + 1 + + + CIRC + Circular mode + 8 + 1 + + + DIR + Data transfer direction + 6 + 2 + + + PFCTRL + Peripheral flow controller + 5 + 1 + + + TCIE + Transfer complete interrupt + enable + 4 + 1 + + + HTIE + Half transfer interrupt + enable + 3 + 1 + + + TEIE + Transfer error interrupt + enable + 2 + 1 + + + DMEIE + Direct mode error interrupt + enable + 1 + 1 + + + EN + Stream enable / flag stream ready when + read low + 0 + 1 + + + + + S7NDTR + S7NDTR + stream x number of data + register + 0xBC + 0x20 + read-write + 0x00000000 + + + NDT + Number of data items to + transfer + 0 + 16 + + + + + S7PAR + S7PAR + stream x peripheral address + register + 0xC0 + 0x20 + read-write + 0x00000000 + + + PA + Peripheral address + 0 + 32 + + + + + S7M0AR + S7M0AR + stream x memory 0 address + register + 0xC4 + 0x20 + read-write + 0x00000000 + + + M0A + Memory 0 address + 0 + 32 + + + + + S7M1AR + S7M1AR + stream x memory 1 address + register + 0xC8 + 0x20 + read-write + 0x00000000 + + + M1A + Memory 1 address (used in case of Double + buffer mode) + 0 + 32 + + + + + S7FCR + S7FCR + stream x FIFO control register + 0xCC + 0x20 + 0x00000021 + + + FEIE + FIFO error interrupt + enable + 7 + 1 + read-write + + + FS + FIFO status + 3 + 3 + read-only + + + DMDIS + Direct mode disable + 2 + 1 + read-write + + + FTH + FIFO threshold selection + 0 + 2 + read-write + + + + + + + DMA2 + 0x40020400 + + DMA_STR2 + DMA1 Stream2 + 13 + + + DMA_STR3 + DMA1 Stream3 + 14 + + + DMA_STR4 + DMA1 Stream4 + 15 + + + DMA_STR5 + DMA1 Stream5 + 16 + + + DMA_STR6 + DMA1 Stream6 + 17 + + + DMA2_STR0 + DMA2 Stream0 interrupt + 56 + + + DMA2_STR1 + DMA2 Stream1 interrupt + 57 + + + DMA2_STR2 + DMA2 Stream2 interrupt + 58 + + + DMA2_STR3 + DMA2 Stream3 interrupt + 59 + + + DMA2_STR4 + DMA2 Stream4 interrupt + 60 + + + DMA2_STR5 + DMA2 Stream5 interrupt + 68 + + + DMA2_STR6 + DMA2 Stream6 interrupt + 69 + + + DMA2_STR7 + DMA2 Stream7 interrupt + 70 + + + + HRTIM_Master + High Resolution Timer: Master + Timers + HRTIM + 0x40017400 + + 0x0 + 0x80 + registers + + + + MCR + MCR + Master Timer Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + BRSTDMA + Burst DMA Update + 30 + 2 + + + MREPU + Master Timer Repetition + update + 29 + 1 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + TECEN + Timer E counter enable + 21 + 1 + + + TDCEN + Timer D counter enable + 20 + 1 + + + TCCEN + Timer C counter enable + 19 + 1 + + + TBCEN + Timer B counter enable + 18 + 1 + + + TACEN + Timer A counter enable + 17 + 1 + + + MCEN + Master Counter enable + 16 + 1 + + + SYNC_SRC + Synchronization source + 14 + 2 + + + SYNC_OUT + Synchronization output + 12 + 2 + + + SYNCSTRTM + Synchronization Starts + Master + 11 + 1 + + + SYNCRSTM + Synchronization Resets + Master + 10 + 1 + + + SYNC_IN + ynchronization input + 8 + 2 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Master Re-triggerable mode + 4 + 1 + + + CONT + Master Continuous mode + 3 + 1 + + + CK_PSC + HRTIM Master Clock + prescaler + 0 + 3 + + + + + MISR + MISR + Master Timer Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + MUPD + Master Update Interrupt + Flag + 6 + 1 + + + SYNC + Sync Input Interrupt Flag + 5 + 1 + + + MREP + Master Repetition Interrupt + Flag + 4 + 1 + + + MCMP4 + Master Compare 4 Interrupt + Flag + 3 + 1 + + + MCMP3 + Master Compare 3 Interrupt + Flag + 2 + 1 + + + MCMP2 + Master Compare 2 Interrupt + Flag + 1 + 1 + + + MCMP1 + Master Compare 1 Interrupt + Flag + 0 + 1 + + + + + MICR + MICR + Master Timer Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + MUPDC + Master update Interrupt flag + clear + 6 + 1 + + + SYNCC + Sync Input Interrupt flag + clear + 5 + 1 + + + MREPC + Repetition Interrupt flag + clear + 4 + 1 + + + MCMP4C + Master Compare 4 Interrupt flag + clear + 3 + 1 + + + MCMP3C + Master Compare 3 Interrupt flag + clear + 2 + 1 + + + MCMP2C + Master Compare 2 Interrupt flag + clear + 1 + 1 + + + MCMP1C + Master Compare 1 Interrupt flag + clear + 0 + 1 + + + + + MDIER4 + MDIER4 + MDIER4 + 0xC + 0x20 + read-write + 0x00000000 + + + MUPDDE + MUPDDE + 22 + 1 + + + SYNCDE + SYNCDE + 21 + 1 + + + MREPDE + MREPDE + 20 + 1 + + + MCMP4DE + MCMP4DE + 19 + 1 + + + MCMP3DE + MCMP3DE + 18 + 1 + + + MCMP2DE + MCMP2DE + 17 + 1 + + + MCMP1DE + MCMP1DE + 16 + 1 + + + MUPDIE + MUPDIE + 6 + 1 + + + SYNCIE + SYNCIE + 5 + 1 + + + MREPIE + MREPIE + 4 + 1 + + + MCMP4IE + MCMP4IE + 3 + 1 + + + MCMP3IE + MCMP3IE + 2 + 1 + + + MCMP2IE + MCMP2IE + 1 + 1 + + + MCMP1IE + MCMP1IE + 0 + 1 + + + + + MCNTR + MCNTR + Master Timer Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + MCNT + Counter value + 0 + 16 + + + + + MPER + MPER + Master Timer Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + MPER + Master Timer Period value + 0 + 16 + + + + + MREP + MREP + Master Timer Repetition + Register + 0x18 + 0x20 + read-write + 0x00000000 + + + MREP + Master Timer Repetition counter + value + 0 + 8 + + + + + MCMP1R + MCMP1R + Master Timer Compare 1 + Register + 0x1C + 0x20 + read-write + 0x00000000 + + + MCMP1 + Master Timer Compare 1 + value + 0 + 16 + + + + + MCMP2R + MCMP2R + Master Timer Compare 2 + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + MCMP2 + Master Timer Compare 2 + value + 0 + 16 + + + + + MCMP3R + MCMP3R + Master Timer Compare 3 + Register + 0x28 + 0x20 + read-write + 0x00000000 + + + MCMP3 + Master Timer Compare 3 + value + 0 + 16 + + + + + MCMP4R + MCMP4R + Master Timer Compare 4 + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + MCMP4 + Master Timer Compare 4 + value + 0 + 16 + + + + + + + HRTIM_TIMA + High Resolution Timer: TIMA + HRTIM + 0x40017480 + + 0x0 + 0x80 + registers + + + HRTIM1_MST + HRTIM1 master timer interrupt + 103 + + + HRTIM1_FLT + HRTIM1 fault interrupt + 109 + + + + TIMACR + TIMACR + Timerx Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + UPDGAT + Update Gating + 28 + 4 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + MSTU + Master Timer update + 24 + 1 + + + TEU + TEU + 23 + 1 + + + TDU + TDU + 22 + 1 + + + TCU + TCU + 21 + 1 + + + TBU + TBU + 20 + 1 + + + TxRSTU + Timerx reset update + 18 + 1 + + + TxREPU + Timer x Repetition update + 17 + 1 + + + DELCMP4 + Delayed CMP4 mode + 14 + 2 + + + DELCMP2 + Delayed CMP2 mode + 12 + 2 + + + SYNCSTRTx + Synchronization Starts Timer + x + 11 + 1 + + + SYNCRSTx + Synchronization Resets Timer + x + 10 + 1 + + + PSHPLL + Push-Pull mode enable + 6 + 1 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Re-triggerable mode + 4 + 1 + + + CONT + Continuous mode + 3 + 1 + + + CK_PSCx + HRTIM Timer x Clock + prescaler + 0 + 3 + + + + + TIMAISR + TIMAISR + Timerx Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + O2STAT + Output 2 State + 19 + 1 + + + O1STAT + Output 1 State + 18 + 1 + + + IPPSTAT + Idle Push Pull Status + 17 + 1 + + + CPPSTAT + Current Push Pull Status + 16 + 1 + + + DLYPRT + Delayed Protection Flag + 14 + 1 + + + RST + Reset Interrupt Flag + 13 + 1 + + + RSTx2 + Output 2 Reset Interrupt + Flag + 12 + 1 + + + SETx2 + Output 2 Set Interrupt + Flag + 11 + 1 + + + RSTx1 + Output 1 Reset Interrupt + Flag + 10 + 1 + + + SETx1 + Output 1 Set Interrupt + Flag + 9 + 1 + + + CPT2 + Capture2 Interrupt Flag + 8 + 1 + + + CPT1 + Capture1 Interrupt Flag + 7 + 1 + + + UPD + Update Interrupt Flag + 6 + 1 + + + REP + Repetition Interrupt Flag + 4 + 1 + + + CMP4 + Compare 4 Interrupt Flag + 3 + 1 + + + CMP3 + Compare 3 Interrupt Flag + 2 + 1 + + + CMP2 + Compare 2 Interrupt Flag + 1 + 1 + + + CMP1 + Compare 1 Interrupt Flag + 0 + 1 + + + + + TIMAICR + TIMAICR + Timerx Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + DLYPRTC + Delayed Protection Flag + Clear + 14 + 1 + + + RSTC + Reset Interrupt flag Clear + 13 + 1 + + + RSTx2C + Output 2 Reset flag Clear + 12 + 1 + + + SET2xC + Output 2 Set flag Clear + 11 + 1 + + + RSTx1C + Output 1 Reset flag Clear + 10 + 1 + + + SET1xC + Output 1 Set flag Clear + 9 + 1 + + + CPT2C + Capture2 Interrupt flag + Clear + 8 + 1 + + + CPT1C + Capture1 Interrupt flag + Clear + 7 + 1 + + + UPDC + Update Interrupt flag + Clear + 6 + 1 + + + REPC + Repetition Interrupt flag + Clear + 4 + 1 + + + CMP4C + Compare 4 Interrupt flag + Clear + 3 + 1 + + + CMP3C + Compare 3 Interrupt flag + Clear + 2 + 1 + + + CMP2C + Compare 2 Interrupt flag + Clear + 1 + 1 + + + CMP1C + Compare 1 Interrupt flag + Clear + 0 + 1 + + + + + TIMADIER5 + TIMADIER5 + TIMxDIER5 + 0xC + 0x20 + read-write + 0x00000000 + + + DLYPRTDE + DLYPRTDE + 30 + 1 + + + RSTDE + RSTDE + 29 + 1 + + + RSTx2DE + RSTx2DE + 28 + 1 + + + SETx2DE + SETx2DE + 27 + 1 + + + RSTx1DE + RSTx1DE + 26 + 1 + + + SET1xDE + SET1xDE + 25 + 1 + + + CPT2DE + CPT2DE + 24 + 1 + + + CPT1DE + CPT1DE + 23 + 1 + + + UPDDE + UPDDE + 22 + 1 + + + REPDE + REPDE + 20 + 1 + + + CMP4DE + CMP4DE + 19 + 1 + + + CMP3DE + CMP3DE + 18 + 1 + + + CMP2DE + CMP2DE + 17 + 1 + + + CMP1DE + CMP1DE + 16 + 1 + + + DLYPRTIE + DLYPRTIE + 14 + 1 + + + RSTIE + RSTIE + 13 + 1 + + + RSTx2IE + RSTx2IE + 12 + 1 + + + SETx2IE + SETx2IE + 11 + 1 + + + RSTx1IE + RSTx1IE + 10 + 1 + + + SET1xIE + SET1xIE + 9 + 1 + + + CPT2IE + CPT2IE + 8 + 1 + + + CPT1IE + CPT1IE + 7 + 1 + + + UPDIE + UPDIE + 6 + 1 + + + REPIE + REPIE + 4 + 1 + + + CMP4IE + CMP4IE + 3 + 1 + + + CMP3IE + CMP3IE + 2 + 1 + + + CMP2IE + CMP2IE + 1 + 1 + + + CMP1IE + CMP1IE + 0 + 1 + + + + + CNTAR + CNTAR + Timerx Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTx + Timerx Counter value + 0 + 16 + + + + + PERAR + PERAR + Timerx Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + PERx + Timerx Period value + 0 + 16 + + + + + REPAR + REPAR + Timerx Repetition Register + 0x18 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition counter + value + 0 + 8 + + + + + CMP1AR + CMP1AR + Timerx Compare 1 Register + 0x1C + 0x20 + read-write + 0x00000000 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP1CAR + CMP1CAR + Timerx Compare 1 Compound + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition value (aliased from + HRTIM_REPx register) + 16 + 8 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP2AR + CMP2AR + Timerx Compare 2 Register + 0x24 + 0x20 + read-write + 0x00000000 + + + CMP2x + Timerx Compare 2 value + 0 + 16 + + + + + CMP3AR + CMP3AR + Timerx Compare 3 Register + 0x28 + 0x20 + read-write + 0x00000000 + + + CMP3x + Timerx Compare 3 value + 0 + 16 + + + + + CMP4AR + CMP4AR + Timerx Compare 4 Register + 0x2C + 0x20 + read-write + 0x00000000 + + + CMP4x + Timerx Compare 4 value + 0 + 16 + + + + + CPT1AR + CPT1AR + Timerx Capture 1 Register + 0x30 + 0x20 + read-only + 0x00000000 + + + CPT1x + Timerx Capture 1 value + 0 + 16 + + + + + CPT2AR + CPT2AR + Timerx Capture 2 Register + 0x34 + 0x20 + read-only + 0x00000000 + + + CPT2x + Timerx Capture 2 value + 0 + 16 + + + + + DTAR + DTAR + Timerx Deadtime Register + 0x38 + 0x20 + read-write + 0x00000000 + + + DTFLKx + Deadtime Falling Lock + 31 + 1 + + + DTFSLKx + Deadtime Falling Sign Lock + 30 + 1 + + + SDTFx + Sign Deadtime Falling + value + 25 + 1 + + + DTFx + Deadtime Falling value + 16 + 9 + + + DTRLKx + Deadtime Rising Lock + 15 + 1 + + + DTRSLKx + Deadtime Rising Sign Lock + 14 + 1 + + + DTPRSC + Deadtime Prescaler + 10 + 3 + + + SDTRx + Sign Deadtime Rising value + 9 + 1 + + + DTRx + Deadtime Rising value + 0 + 9 + + + + + SETA1R + SETA1R + Timerx Output1 Set Register + 0x3C + 0x20 + read-write + 0x00000000 + + + UPDATE + Registers update (transfer preload to + active) + 31 + 1 + + + EXTEVNT10 + External Event 10 + 30 + 1 + + + EXTEVNT9 + External Event 9 + 29 + 1 + + + EXTEVNT8 + External Event 8 + 28 + 1 + + + EXTEVNT7 + External Event 7 + 27 + 1 + + + EXTEVNT6 + External Event 6 + 26 + 1 + + + EXTEVNT5 + External Event 5 + 25 + 1 + + + EXTEVNT4 + External Event 4 + 24 + 1 + + + EXTEVNT3 + External Event 3 + 23 + 1 + + + EXTEVNT2 + External Event 2 + 22 + 1 + + + EXTEVNT1 + External Event 1 + 21 + 1 + + + TIMEVNT9 + Timer Event 9 + 20 + 1 + + + TIMEVNT8 + Timer Event 8 + 19 + 1 + + + TIMEVNT7 + Timer Event 7 + 18 + 1 + + + TIMEVNT6 + Timer Event 6 + 17 + 1 + + + TIMEVNT5 + Timer Event 5 + 16 + 1 + + + TIMEVNT4 + Timer Event 4 + 15 + 1 + + + TIMEVNT3 + Timer Event 3 + 14 + 1 + + + TIMEVNT2 + Timer Event 2 + 13 + 1 + + + TIMEVNT1 + Timer Event 1 + 12 + 1 + + + MSTCMP4 + Master Compare 4 + 11 + 1 + + + MSTCMP3 + Master Compare 3 + 10 + 1 + + + MSTCMP2 + Master Compare 2 + 9 + 1 + + + MSTCMP1 + Master Compare 1 + 8 + 1 + + + MSTPER + Master Period + 7 + 1 + + + CMP4 + Timer A compare 4 + 6 + 1 + + + CMP3 + Timer A compare 3 + 5 + 1 + + + CMP2 + Timer A compare 2 + 4 + 1 + + + CMP1 + Timer A compare 1 + 3 + 1 + + + PER + Timer A Period + 2 + 1 + + + RESYNC + Timer A resynchronizaton + 1 + 1 + + + SST + Software Set trigger + 0 + 1 + + + + + RSTA1R + RSTA1R + Timerx Output1 Reset Register + 0x40 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + SETA2R + SETA2R + Timerx Output2 Set Register + 0x44 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SST + SST + 0 + 1 + + + + + RSTA2R + RSTA2R + Timerx Output2 Reset Register + 0x48 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + EEFAR1 + EEFAR1 + Timerx External Event Filtering Register + 1 + 0x4C + 0x20 + read-write + 0x00000000 + + + EE5FLTR + External Event 5 filter + 25 + 4 + + + EE5LTCH + External Event 5 latch + 24 + 1 + + + EE4FLTR + External Event 4 filter + 19 + 4 + + + EE4LTCH + External Event 4 latch + 18 + 1 + + + EE3FLTR + External Event 3 filter + 13 + 4 + + + EE3LTCH + External Event 3 latch + 12 + 1 + + + EE2FLTR + External Event 2 filter + 7 + 4 + + + EE2LTCH + External Event 2 latch + 6 + 1 + + + EE1FLTR + External Event 1 filter + 1 + 4 + + + EE1LTCH + External Event 1 latch + 0 + 1 + + + + + EEFAR2 + EEFAR2 + Timerx External Event Filtering Register + 2 + 0x50 + 0x20 + read-write + 0x00000000 + + + EE10FLTR + External Event 10 filter + 25 + 4 + + + EE10LTCH + External Event 10 latch + 24 + 1 + + + EE9FLTR + External Event 9 filter + 19 + 4 + + + EE9LTCH + External Event 9 latch + 18 + 1 + + + EE8FLTR + External Event 8 filter + 13 + 4 + + + EE8LTCH + External Event 8 latch + 12 + 1 + + + EE7FLTR + External Event 7 filter + 7 + 4 + + + EE7LTCH + External Event 7 latch + 6 + 1 + + + EE6FLTR + External Event 6 filter + 1 + 4 + + + EE6LTCH + External Event 6 latch + 0 + 1 + + + + + RSTAR + RSTAR + TimerA Reset Register + 0x54 + 0x20 + read-write + 0x00000000 + + + TIMECMP4 + Timer E Compare 4 + 30 + 1 + + + TIMECMP2 + Timer E Compare 2 + 29 + 1 + + + TIMECMP1 + Timer E Compare 1 + 28 + 1 + + + TIMDCMP4 + Timer D Compare 4 + 27 + 1 + + + TIMDCMP2 + Timer D Compare 2 + 26 + 1 + + + TIMDCMP1 + Timer D Compare 1 + 25 + 1 + + + TIMCCMP4 + Timer C Compare 4 + 24 + 1 + + + TIMCCMP2 + Timer C Compare 2 + 23 + 1 + + + TIMCCMP1 + Timer C Compare 1 + 22 + 1 + + + TIMBCMP4 + Timer B Compare 4 + 21 + 1 + + + TIMBCMP2 + Timer B Compare 2 + 20 + 1 + + + TIMBCMP1 + Timer B Compare 1 + 19 + 1 + + + EXTEVNT10 + External Event 10 + 18 + 1 + + + EXTEVNT9 + External Event 9 + 17 + 1 + + + EXTEVNT8 + External Event 8 + 16 + 1 + + + EXTEVNT7 + External Event 7 + 15 + 1 + + + EXTEVNT6 + External Event 6 + 14 + 1 + + + EXTEVNT5 + External Event 5 + 13 + 1 + + + EXTEVNT4 + External Event 4 + 12 + 1 + + + EXTEVNT3 + External Event 3 + 11 + 1 + + + EXTEVNT2 + External Event 2 + 10 + 1 + + + EXTEVNT1 + External Event 1 + 9 + 1 + + + MSTCMP4 + Master compare 4 + 8 + 1 + + + MSTCMP3 + Master compare 3 + 7 + 1 + + + MSTCMP2 + Master compare 2 + 6 + 1 + + + MSTCMP1 + Master compare 1 + 5 + 1 + + + MSTPER + Master timer Period + 4 + 1 + + + CMP4 + Timer A compare 4 reset + 3 + 1 + + + CMP2 + Timer A compare 2 reset + 2 + 1 + + + UPDT + Timer A Update reset + 1 + 1 + + + + + CHPAR + CHPAR + Timerx Chopper Register + 0x58 + 0x20 + read-write + 0x00000000 + + + STRTPW + STRTPW + 7 + 4 + + + CHPDTY + Timerx chopper duty cycle + value + 4 + 3 + + + CHPFRQ + Timerx carrier frequency + value + 0 + 4 + + + + + CPT1ACR + CPT1ACR + Timerx Capture 2 Control + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + CPT2ACR + CPT2ACR + CPT2xCR + 0x60 + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + OUTAR + OUTAR + Timerx Output Register + 0x64 + 0x20 + read-write + 0x00000000 + + + DIDL2 + Output 2 Deadtime upon burst mode Idle + entry + 23 + 1 + + + CHP2 + Output 2 Chopper enable + 22 + 1 + + + FAULT2 + Output 2 Fault state + 20 + 2 + + + IDLES2 + Output 2 Idle State + 19 + 1 + + + IDLEM2 + Output 2 Idle mode + 18 + 1 + + + POL2 + Output 2 polarity + 17 + 1 + + + DLYPRT + Delayed Protection + 10 + 3 + + + DLYPRTEN + Delayed Protection Enable + 9 + 1 + + + DTEN + Deadtime enable + 8 + 1 + + + DIDL1 + Output 1 Deadtime upon burst mode Idle + entry + 7 + 1 + + + CHP1 + Output 1 Chopper enable + 6 + 1 + + + FAULT1 + Output 1 Fault state + 4 + 2 + + + IDLES1 + Output 1 Idle State + 3 + 1 + + + IDLEM1 + Output 1 Idle mode + 2 + 1 + + + POL1 + Output 1 polarity + 1 + 1 + + + + + FLTAR + FLTAR + Timerx Fault Register + 0x68 + 0x20 + read-write + 0x00000000 + + + FLTLCK + Fault sources Lock + 31 + 1 + + + FLT5EN + Fault 5 enable + 4 + 1 + + + FLT4EN + Fault 4 enable + 3 + 1 + + + FLT3EN + Fault 3 enable + 2 + 1 + + + FLT2EN + Fault 2 enable + 1 + 1 + + + FLT1EN + Fault 1 enable + 0 + 1 + + + + + + + HRTIM_TIMB + High Resolution Timer: TIMB + HRTIM + 0x40017500 + + 0x0 + 0x80 + registers + + + HRTIM1_TIMA + HRTIM1 timer A interrupt + 104 + + + + TIMBCR + TIMBCR + Timerx Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + UPDGAT + Update Gating + 28 + 4 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + MSTU + Master Timer update + 24 + 1 + + + TEU + TEU + 23 + 1 + + + TDU + TDU + 22 + 1 + + + TCU + TCU + 21 + 1 + + + TBU + TBU + 20 + 1 + + + TxRSTU + Timerx reset update + 18 + 1 + + + TxREPU + Timer x Repetition update + 17 + 1 + + + DELCMP4 + Delayed CMP4 mode + 14 + 2 + + + DELCMP2 + Delayed CMP2 mode + 12 + 2 + + + SYNCSTRTx + Synchronization Starts Timer + x + 11 + 1 + + + SYNCRSTx + Synchronization Resets Timer + x + 10 + 1 + + + PSHPLL + Push-Pull mode enable + 6 + 1 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Re-triggerable mode + 4 + 1 + + + CONT + Continuous mode + 3 + 1 + + + CK_PSCx + HRTIM Timer x Clock + prescaler + 0 + 3 + + + + + TIMBISR + TIMBISR + Timerx Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + O2STAT + Output 2 State + 19 + 1 + + + O1STAT + Output 1 State + 18 + 1 + + + IPPSTAT + Idle Push Pull Status + 17 + 1 + + + CPPSTAT + Current Push Pull Status + 16 + 1 + + + DLYPRT + Delayed Protection Flag + 14 + 1 + + + RST + Reset Interrupt Flag + 13 + 1 + + + RSTx2 + Output 2 Reset Interrupt + Flag + 12 + 1 + + + SETx2 + Output 2 Set Interrupt + Flag + 11 + 1 + + + RSTx1 + Output 1 Reset Interrupt + Flag + 10 + 1 + + + SETx1 + Output 1 Set Interrupt + Flag + 9 + 1 + + + CPT2 + Capture2 Interrupt Flag + 8 + 1 + + + CPT1 + Capture1 Interrupt Flag + 7 + 1 + + + UPD + Update Interrupt Flag + 6 + 1 + + + REP + Repetition Interrupt Flag + 4 + 1 + + + CMP4 + Compare 4 Interrupt Flag + 3 + 1 + + + CMP3 + Compare 3 Interrupt Flag + 2 + 1 + + + CMP2 + Compare 2 Interrupt Flag + 1 + 1 + + + CMP1 + Compare 1 Interrupt Flag + 0 + 1 + + + + + TIMBICR + TIMBICR + Timerx Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + DLYPRTC + Delayed Protection Flag + Clear + 14 + 1 + + + RSTC + Reset Interrupt flag Clear + 13 + 1 + + + RSTx2C + Output 2 Reset flag Clear + 12 + 1 + + + SET2xC + Output 2 Set flag Clear + 11 + 1 + + + RSTx1C + Output 1 Reset flag Clear + 10 + 1 + + + SET1xC + Output 1 Set flag Clear + 9 + 1 + + + CPT2C + Capture2 Interrupt flag + Clear + 8 + 1 + + + CPT1C + Capture1 Interrupt flag + Clear + 7 + 1 + + + UPDC + Update Interrupt flag + Clear + 6 + 1 + + + REPC + Repetition Interrupt flag + Clear + 4 + 1 + + + CMP4C + Compare 4 Interrupt flag + Clear + 3 + 1 + + + CMP3C + Compare 3 Interrupt flag + Clear + 2 + 1 + + + CMP2C + Compare 2 Interrupt flag + Clear + 1 + 1 + + + CMP1C + Compare 1 Interrupt flag + Clear + 0 + 1 + + + + + TIMBDIER5 + TIMBDIER5 + TIMxDIER5 + 0xC + 0x20 + read-write + 0x00000000 + + + DLYPRTDE + DLYPRTDE + 30 + 1 + + + RSTDE + RSTDE + 29 + 1 + + + RSTx2DE + RSTx2DE + 28 + 1 + + + SETx2DE + SETx2DE + 27 + 1 + + + RSTx1DE + RSTx1DE + 26 + 1 + + + SET1xDE + SET1xDE + 25 + 1 + + + CPT2DE + CPT2DE + 24 + 1 + + + CPT1DE + CPT1DE + 23 + 1 + + + UPDDE + UPDDE + 22 + 1 + + + REPDE + REPDE + 20 + 1 + + + CMP4DE + CMP4DE + 19 + 1 + + + CMP3DE + CMP3DE + 18 + 1 + + + CMP2DE + CMP2DE + 17 + 1 + + + CMP1DE + CMP1DE + 16 + 1 + + + DLYPRTIE + DLYPRTIE + 14 + 1 + + + RSTIE + RSTIE + 13 + 1 + + + RSTx2IE + RSTx2IE + 12 + 1 + + + SETx2IE + SETx2IE + 11 + 1 + + + RSTx1IE + RSTx1IE + 10 + 1 + + + SET1xIE + SET1xIE + 9 + 1 + + + CPT2IE + CPT2IE + 8 + 1 + + + CPT1IE + CPT1IE + 7 + 1 + + + UPDIE + UPDIE + 6 + 1 + + + REPIE + REPIE + 4 + 1 + + + CMP4IE + CMP4IE + 3 + 1 + + + CMP3IE + CMP3IE + 2 + 1 + + + CMP2IE + CMP2IE + 1 + 1 + + + CMP1IE + CMP1IE + 0 + 1 + + + + + CNTR + CNTR + Timerx Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTx + Timerx Counter value + 0 + 16 + + + + + PERBR + PERBR + Timerx Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + PERx + Timerx Period value + 0 + 16 + + + + + REPBR + REPBR + Timerx Repetition Register + 0x18 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition counter + value + 0 + 8 + + + + + CMP1BR + CMP1BR + Timerx Compare 1 Register + 0x1C + 0x20 + read-write + 0x00000000 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP1CBR + CMP1CBR + Timerx Compare 1 Compound + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition value (aliased from + HRTIM_REPx register) + 16 + 8 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP2BR + CMP2BR + Timerx Compare 2 Register + 0x24 + 0x20 + read-write + 0x00000000 + + + CMP2x + Timerx Compare 2 value + 0 + 16 + + + + + CMP3BR + CMP3BR + Timerx Compare 3 Register + 0x28 + 0x20 + read-write + 0x00000000 + + + CMP3x + Timerx Compare 3 value + 0 + 16 + + + + + CMP4BR + CMP4BR + Timerx Compare 4 Register + 0x2C + 0x20 + read-write + 0x00000000 + + + CMP4x + Timerx Compare 4 value + 0 + 16 + + + + + CPT1BR + CPT1BR + Timerx Capture 1 Register + 0x30 + 0x20 + read-only + 0x00000000 + + + CPT1x + Timerx Capture 1 value + 0 + 16 + + + + + CPT2BR + CPT2BR + Timerx Capture 2 Register + 0x34 + 0x20 + read-only + 0x00000000 + + + CPT2x + Timerx Capture 2 value + 0 + 16 + + + + + DTBR + DTBR + Timerx Deadtime Register + 0x38 + 0x20 + read-write + 0x00000000 + + + DTFLKx + Deadtime Falling Lock + 31 + 1 + + + DTFSLKx + Deadtime Falling Sign Lock + 30 + 1 + + + SDTFx + Sign Deadtime Falling + value + 25 + 1 + + + DTFx + Deadtime Falling value + 16 + 9 + + + DTRLKx + Deadtime Rising Lock + 15 + 1 + + + DTRSLKx + Deadtime Rising Sign Lock + 14 + 1 + + + DTPRSC + Deadtime Prescaler + 10 + 3 + + + SDTRx + Sign Deadtime Rising value + 9 + 1 + + + DTRx + Deadtime Rising value + 0 + 9 + + + + + SETB1R + SETB1R + Timerx Output1 Set Register + 0x3C + 0x20 + read-write + 0x00000000 + + + UPDATE + Registers update (transfer preload to + active) + 31 + 1 + + + EXTEVNT10 + External Event 10 + 30 + 1 + + + EXTEVNT9 + External Event 9 + 29 + 1 + + + EXTEVNT8 + External Event 8 + 28 + 1 + + + EXTEVNT7 + External Event 7 + 27 + 1 + + + EXTEVNT6 + External Event 6 + 26 + 1 + + + EXTEVNT5 + External Event 5 + 25 + 1 + + + EXTEVNT4 + External Event 4 + 24 + 1 + + + EXTEVNT3 + External Event 3 + 23 + 1 + + + EXTEVNT2 + External Event 2 + 22 + 1 + + + EXTEVNT1 + External Event 1 + 21 + 1 + + + TIMEVNT9 + Timer Event 9 + 20 + 1 + + + TIMEVNT8 + Timer Event 8 + 19 + 1 + + + TIMEVNT7 + Timer Event 7 + 18 + 1 + + + TIMEVNT6 + Timer Event 6 + 17 + 1 + + + TIMEVNT5 + Timer Event 5 + 16 + 1 + + + TIMEVNT4 + Timer Event 4 + 15 + 1 + + + TIMEVNT3 + Timer Event 3 + 14 + 1 + + + TIMEVNT2 + Timer Event 2 + 13 + 1 + + + TIMEVNT1 + Timer Event 1 + 12 + 1 + + + MSTCMP4 + Master Compare 4 + 11 + 1 + + + MSTCMP3 + Master Compare 3 + 10 + 1 + + + MSTCMP2 + Master Compare 2 + 9 + 1 + + + MSTCMP1 + Master Compare 1 + 8 + 1 + + + MSTPER + Master Period + 7 + 1 + + + CMP4 + Timer A compare 4 + 6 + 1 + + + CMP3 + Timer A compare 3 + 5 + 1 + + + CMP2 + Timer A compare 2 + 4 + 1 + + + CMP1 + Timer A compare 1 + 3 + 1 + + + PER + Timer A Period + 2 + 1 + + + RESYNC + Timer A resynchronizaton + 1 + 1 + + + SST + Software Set trigger + 0 + 1 + + + + + RSTB1R + RSTB1R + Timerx Output1 Reset Register + 0x40 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + SETB2R + SETB2R + Timerx Output2 Set Register + 0x44 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SST + SST + 0 + 1 + + + + + RSTB2R + RSTB2R + Timerx Output2 Reset Register + 0x48 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + EEFBR1 + EEFBR1 + Timerx External Event Filtering Register + 1 + 0x4C + 0x20 + read-write + 0x00000000 + + + EE5FLTR + External Event 5 filter + 25 + 4 + + + EE5LTCH + External Event 5 latch + 24 + 1 + + + EE4FLTR + External Event 4 filter + 19 + 4 + + + EE4LTCH + External Event 4 latch + 18 + 1 + + + EE3FLTR + External Event 3 filter + 13 + 4 + + + EE3LTCH + External Event 3 latch + 12 + 1 + + + EE2FLTR + External Event 2 filter + 7 + 4 + + + EE2LTCH + External Event 2 latch + 6 + 1 + + + EE1FLTR + External Event 1 filter + 1 + 4 + + + EE1LTCH + External Event 1 latch + 0 + 1 + + + + + EEFBR2 + EEFBR2 + Timerx External Event Filtering Register + 2 + 0x50 + 0x20 + read-write + 0x00000000 + + + EE10FLTR + External Event 10 filter + 25 + 4 + + + EE10LTCH + External Event 10 latch + 24 + 1 + + + EE9FLTR + External Event 9 filter + 19 + 4 + + + EE9LTCH + External Event 9 latch + 18 + 1 + + + EE8FLTR + External Event 8 filter + 13 + 4 + + + EE8LTCH + External Event 8 latch + 12 + 1 + + + EE7FLTR + External Event 7 filter + 7 + 4 + + + EE7LTCH + External Event 7 latch + 6 + 1 + + + EE6FLTR + External Event 6 filter + 1 + 4 + + + EE6LTCH + External Event 6 latch + 0 + 1 + + + + + RSTBR + RSTBR + TimerA Reset Register + 0x54 + 0x20 + read-write + 0x00000000 + + + TIMECMP4 + Timer E Compare 4 + 30 + 1 + + + TIMECMP2 + Timer E Compare 2 + 29 + 1 + + + TIMECMP1 + Timer E Compare 1 + 28 + 1 + + + TIMDCMP4 + Timer D Compare 4 + 27 + 1 + + + TIMDCMP2 + Timer D Compare 2 + 26 + 1 + + + TIMDCMP1 + Timer D Compare 1 + 25 + 1 + + + TIMCCMP4 + Timer C Compare 4 + 24 + 1 + + + TIMCCMP2 + Timer C Compare 2 + 23 + 1 + + + TIMCCMP1 + Timer C Compare 1 + 22 + 1 + + + TIMACMP4 + Timer A Compare 4 + 21 + 1 + + + TIMACMP2 + Timer A Compare 2 + 20 + 1 + + + TIMACMP1 + Timer A Compare 1 + 19 + 1 + + + EXTEVNT10 + External Event 10 + 18 + 1 + + + EXTEVNT9 + External Event 9 + 17 + 1 + + + EXTEVNT8 + External Event 8 + 16 + 1 + + + EXTEVNT7 + External Event 7 + 15 + 1 + + + EXTEVNT6 + External Event 6 + 14 + 1 + + + EXTEVNT5 + External Event 5 + 13 + 1 + + + EXTEVNT4 + External Event 4 + 12 + 1 + + + EXTEVNT3 + External Event 3 + 11 + 1 + + + EXTEVNT2 + External Event 2 + 10 + 1 + + + EXTEVNT1 + External Event 1 + 9 + 1 + + + MSTCMP4 + Master compare 4 + 8 + 1 + + + MSTCMP3 + Master compare 3 + 7 + 1 + + + MSTCMP2 + Master compare 2 + 6 + 1 + + + MSTCMP1 + Master compare 1 + 5 + 1 + + + MSTPER + Master timer Period + 4 + 1 + + + CMP4 + Timer A compare 4 reset + 3 + 1 + + + CMP2 + Timer A compare 2 reset + 2 + 1 + + + UPDT + Timer A Update reset + 1 + 1 + + + + + CHPBR + CHPBR + Timerx Chopper Register + 0x58 + 0x20 + read-write + 0x00000000 + + + STRTPW + STRTPW + 7 + 4 + + + CHPDTY + Timerx chopper duty cycle + value + 4 + 3 + + + CHPFRQ + Timerx carrier frequency + value + 0 + 4 + + + + + CPT1BCR + CPT1BCR + Timerx Capture 2 Control + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + CPT2BCR + CPT2BCR + CPT2xCR + 0x60 + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + OUTBR + OUTBR + Timerx Output Register + 0x64 + 0x20 + read-write + 0x00000000 + + + DIDL2 + Output 2 Deadtime upon burst mode Idle + entry + 23 + 1 + + + CHP2 + Output 2 Chopper enable + 22 + 1 + + + FAULT2 + Output 2 Fault state + 20 + 2 + + + IDLES2 + Output 2 Idle State + 19 + 1 + + + IDLEM2 + Output 2 Idle mode + 18 + 1 + + + POL2 + Output 2 polarity + 17 + 1 + + + DLYPRT + Delayed Protection + 10 + 3 + + + DLYPRTEN + Delayed Protection Enable + 9 + 1 + + + DTEN + Deadtime enable + 8 + 1 + + + DIDL1 + Output 1 Deadtime upon burst mode Idle + entry + 7 + 1 + + + CHP1 + Output 1 Chopper enable + 6 + 1 + + + FAULT1 + Output 1 Fault state + 4 + 2 + + + IDLES1 + Output 1 Idle State + 3 + 1 + + + IDLEM1 + Output 1 Idle mode + 2 + 1 + + + POL1 + Output 1 polarity + 1 + 1 + + + + + FLTBR + FLTBR + Timerx Fault Register + 0x68 + 0x20 + read-write + 0x00000000 + + + FLTLCK + Fault sources Lock + 31 + 1 + + + FLT5EN + Fault 5 enable + 4 + 1 + + + FLT4EN + Fault 4 enable + 3 + 1 + + + FLT3EN + Fault 3 enable + 2 + 1 + + + FLT2EN + Fault 2 enable + 1 + 1 + + + FLT1EN + Fault 1 enable + 0 + 1 + + + + + + + HRTIM_TIMC + High Resolution Timer: TIMC + HRTIM + 0x40017580 + + 0x0 + 0x80 + registers + + + HRTIM_TIMB + HRTIM1 timer B interrupt + 105 + + + + TIMCCR + TIMCCR + Timerx Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + UPDGAT + Update Gating + 28 + 4 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + MSTU + Master Timer update + 24 + 1 + + + TEU + TEU + 23 + 1 + + + TDU + TDU + 22 + 1 + + + TCU + TCU + 21 + 1 + + + TBU + TBU + 20 + 1 + + + TxRSTU + Timerx reset update + 18 + 1 + + + TxREPU + Timer x Repetition update + 17 + 1 + + + DELCMP4 + Delayed CMP4 mode + 14 + 2 + + + DELCMP2 + Delayed CMP2 mode + 12 + 2 + + + SYNCSTRTx + Synchronization Starts Timer + x + 11 + 1 + + + SYNCRSTx + Synchronization Resets Timer + x + 10 + 1 + + + PSHPLL + Push-Pull mode enable + 6 + 1 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Re-triggerable mode + 4 + 1 + + + CONT + Continuous mode + 3 + 1 + + + CK_PSCx + HRTIM Timer x Clock + prescaler + 0 + 3 + + + + + TIMCISR + TIMCISR + Timerx Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + O2STAT + Output 2 State + 19 + 1 + + + O1STAT + Output 1 State + 18 + 1 + + + IPPSTAT + Idle Push Pull Status + 17 + 1 + + + CPPSTAT + Current Push Pull Status + 16 + 1 + + + DLYPRT + Delayed Protection Flag + 14 + 1 + + + RST + Reset Interrupt Flag + 13 + 1 + + + RSTx2 + Output 2 Reset Interrupt + Flag + 12 + 1 + + + SETx2 + Output 2 Set Interrupt + Flag + 11 + 1 + + + RSTx1 + Output 1 Reset Interrupt + Flag + 10 + 1 + + + SETx1 + Output 1 Set Interrupt + Flag + 9 + 1 + + + CPT2 + Capture2 Interrupt Flag + 8 + 1 + + + CPT1 + Capture1 Interrupt Flag + 7 + 1 + + + UPD + Update Interrupt Flag + 6 + 1 + + + REP + Repetition Interrupt Flag + 4 + 1 + + + CMP4 + Compare 4 Interrupt Flag + 3 + 1 + + + CMP3 + Compare 3 Interrupt Flag + 2 + 1 + + + CMP2 + Compare 2 Interrupt Flag + 1 + 1 + + + CMP1 + Compare 1 Interrupt Flag + 0 + 1 + + + + + TIMCICR + TIMCICR + Timerx Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + DLYPRTC + Delayed Protection Flag + Clear + 14 + 1 + + + RSTC + Reset Interrupt flag Clear + 13 + 1 + + + RSTx2C + Output 2 Reset flag Clear + 12 + 1 + + + SET2xC + Output 2 Set flag Clear + 11 + 1 + + + RSTx1C + Output 1 Reset flag Clear + 10 + 1 + + + SET1xC + Output 1 Set flag Clear + 9 + 1 + + + CPT2C + Capture2 Interrupt flag + Clear + 8 + 1 + + + CPT1C + Capture1 Interrupt flag + Clear + 7 + 1 + + + UPDC + Update Interrupt flag + Clear + 6 + 1 + + + REPC + Repetition Interrupt flag + Clear + 4 + 1 + + + CMP4C + Compare 4 Interrupt flag + Clear + 3 + 1 + + + CMP3C + Compare 3 Interrupt flag + Clear + 2 + 1 + + + CMP2C + Compare 2 Interrupt flag + Clear + 1 + 1 + + + CMP1C + Compare 1 Interrupt flag + Clear + 0 + 1 + + + + + TIMCDIER5 + TIMCDIER5 + TIMxDIER5 + 0xC + 0x20 + read-write + 0x00000000 + + + DLYPRTDE + DLYPRTDE + 30 + 1 + + + RSTDE + RSTDE + 29 + 1 + + + RSTx2DE + RSTx2DE + 28 + 1 + + + SETx2DE + SETx2DE + 27 + 1 + + + RSTx1DE + RSTx1DE + 26 + 1 + + + SET1xDE + SET1xDE + 25 + 1 + + + CPT2DE + CPT2DE + 24 + 1 + + + CPT1DE + CPT1DE + 23 + 1 + + + UPDDE + UPDDE + 22 + 1 + + + REPDE + REPDE + 20 + 1 + + + CMP4DE + CMP4DE + 19 + 1 + + + CMP3DE + CMP3DE + 18 + 1 + + + CMP2DE + CMP2DE + 17 + 1 + + + CMP1DE + CMP1DE + 16 + 1 + + + DLYPRTIE + DLYPRTIE + 14 + 1 + + + RSTIE + RSTIE + 13 + 1 + + + RSTx2IE + RSTx2IE + 12 + 1 + + + SETx2IE + SETx2IE + 11 + 1 + + + RSTx1IE + RSTx1IE + 10 + 1 + + + SET1xIE + SET1xIE + 9 + 1 + + + CPT2IE + CPT2IE + 8 + 1 + + + CPT1IE + CPT1IE + 7 + 1 + + + UPDIE + UPDIE + 6 + 1 + + + REPIE + REPIE + 4 + 1 + + + CMP4IE + CMP4IE + 3 + 1 + + + CMP3IE + CMP3IE + 2 + 1 + + + CMP2IE + CMP2IE + 1 + 1 + + + CMP1IE + CMP1IE + 0 + 1 + + + + + CNTCR + CNTCR + Timerx Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTx + Timerx Counter value + 0 + 16 + + + + + PERCR + PERCR + Timerx Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + PERx + Timerx Period value + 0 + 16 + + + + + REPCR + REPCR + Timerx Repetition Register + 0x18 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition counter + value + 0 + 8 + + + + + CMP1CR + CMP1CR + Timerx Compare 1 Register + 0x1C + 0x20 + read-write + 0x00000000 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP1CCR + CMP1CCR + Timerx Compare 1 Compound + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition value (aliased from + HRTIM_REPx register) + 16 + 8 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP2CR + CMP2CR + Timerx Compare 2 Register + 0x24 + 0x20 + read-write + 0x00000000 + + + CMP2x + Timerx Compare 2 value + 0 + 16 + + + + + CMP3CR + CMP3CR + Timerx Compare 3 Register + 0x28 + 0x20 + read-write + 0x00000000 + + + CMP3x + Timerx Compare 3 value + 0 + 16 + + + + + CMP4CR + CMP4CR + Timerx Compare 4 Register + 0x2C + 0x20 + read-write + 0x00000000 + + + CMP4x + Timerx Compare 4 value + 0 + 16 + + + + + CPT1CR + CPT1CR + Timerx Capture 1 Register + 0x30 + 0x20 + read-only + 0x00000000 + + + CPT1x + Timerx Capture 1 value + 0 + 16 + + + + + CPT2CR + CPT2CR + Timerx Capture 2 Register + 0x34 + 0x20 + read-only + 0x00000000 + + + CPT2x + Timerx Capture 2 value + 0 + 16 + + + + + DTCR + DTCR + Timerx Deadtime Register + 0x38 + 0x20 + read-write + 0x00000000 + + + DTFLKx + Deadtime Falling Lock + 31 + 1 + + + DTFSLKx + Deadtime Falling Sign Lock + 30 + 1 + + + SDTFx + Sign Deadtime Falling + value + 25 + 1 + + + DTFx + Deadtime Falling value + 16 + 9 + + + DTRLKx + Deadtime Rising Lock + 15 + 1 + + + DTRSLKx + Deadtime Rising Sign Lock + 14 + 1 + + + DTPRSC + Deadtime Prescaler + 10 + 3 + + + SDTRx + Sign Deadtime Rising value + 9 + 1 + + + DTRx + Deadtime Rising value + 0 + 9 + + + + + SETC1R + SETC1R + Timerx Output1 Set Register + 0x3C + 0x20 + read-write + 0x00000000 + + + UPDATE + Registers update (transfer preload to + active) + 31 + 1 + + + EXTEVNT10 + External Event 10 + 30 + 1 + + + EXTEVNT9 + External Event 9 + 29 + 1 + + + EXTEVNT8 + External Event 8 + 28 + 1 + + + EXTEVNT7 + External Event 7 + 27 + 1 + + + EXTEVNT6 + External Event 6 + 26 + 1 + + + EXTEVNT5 + External Event 5 + 25 + 1 + + + EXTEVNT4 + External Event 4 + 24 + 1 + + + EXTEVNT3 + External Event 3 + 23 + 1 + + + EXTEVNT2 + External Event 2 + 22 + 1 + + + EXTEVNT1 + External Event 1 + 21 + 1 + + + TIMEVNT9 + Timer Event 9 + 20 + 1 + + + TIMEVNT8 + Timer Event 8 + 19 + 1 + + + TIMEVNT7 + Timer Event 7 + 18 + 1 + + + TIMEVNT6 + Timer Event 6 + 17 + 1 + + + TIMEVNT5 + Timer Event 5 + 16 + 1 + + + TIMEVNT4 + Timer Event 4 + 15 + 1 + + + TIMEVNT3 + Timer Event 3 + 14 + 1 + + + TIMEVNT2 + Timer Event 2 + 13 + 1 + + + TIMEVNT1 + Timer Event 1 + 12 + 1 + + + MSTCMP4 + Master Compare 4 + 11 + 1 + + + MSTCMP3 + Master Compare 3 + 10 + 1 + + + MSTCMP2 + Master Compare 2 + 9 + 1 + + + MSTCMP1 + Master Compare 1 + 8 + 1 + + + MSTPER + Master Period + 7 + 1 + + + CMP4 + Timer A compare 4 + 6 + 1 + + + CMP3 + Timer A compare 3 + 5 + 1 + + + CMP2 + Timer A compare 2 + 4 + 1 + + + CMP1 + Timer A compare 1 + 3 + 1 + + + PER + Timer A Period + 2 + 1 + + + RESYNC + Timer A resynchronizaton + 1 + 1 + + + SST + Software Set trigger + 0 + 1 + + + + + RSTC1R + RSTC1R + Timerx Output1 Reset Register + 0x40 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + SETC2R + SETC2R + Timerx Output2 Set Register + 0x44 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SST + SST + 0 + 1 + + + + + RSTC2R + RSTC2R + Timerx Output2 Reset Register + 0x48 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + EEFCR1 + EEFCR1 + Timerx External Event Filtering Register + 1 + 0x4C + 0x20 + read-write + 0x00000000 + + + EE5FLTR + External Event 5 filter + 25 + 4 + + + EE5LTCH + External Event 5 latch + 24 + 1 + + + EE4FLTR + External Event 4 filter + 19 + 4 + + + EE4LTCH + External Event 4 latch + 18 + 1 + + + EE3FLTR + External Event 3 filter + 13 + 4 + + + EE3LTCH + External Event 3 latch + 12 + 1 + + + EE2FLTR + External Event 2 filter + 7 + 4 + + + EE2LTCH + External Event 2 latch + 6 + 1 + + + EE1FLTR + External Event 1 filter + 1 + 4 + + + EE1LTCH + External Event 1 latch + 0 + 1 + + + + + EEFCR2 + EEFCR2 + Timerx External Event Filtering Register + 2 + 0x50 + 0x20 + read-write + 0x00000000 + + + EE10FLTR + External Event 10 filter + 25 + 4 + + + EE10LTCH + External Event 10 latch + 24 + 1 + + + EE9FLTR + External Event 9 filter + 19 + 4 + + + EE9LTCH + External Event 9 latch + 18 + 1 + + + EE8FLTR + External Event 8 filter + 13 + 4 + + + EE8LTCH + External Event 8 latch + 12 + 1 + + + EE7FLTR + External Event 7 filter + 7 + 4 + + + EE7LTCH + External Event 7 latch + 6 + 1 + + + EE6FLTR + External Event 6 filter + 1 + 4 + + + EE6LTCH + External Event 6 latch + 0 + 1 + + + + + RSTCR + RSTCR + TimerA Reset Register + 0x54 + 0x20 + read-write + 0x00000000 + + + TIMECMP4 + Timer E Compare 4 + 30 + 1 + + + TIMECMP2 + Timer E Compare 2 + 29 + 1 + + + TIMECMP1 + Timer E Compare 1 + 28 + 1 + + + TIMDCMP4 + Timer D Compare 4 + 27 + 1 + + + TIMDCMP2 + Timer D Compare 2 + 26 + 1 + + + TIMDCMP1 + Timer D Compare 1 + 25 + 1 + + + TIMBCMP4 + Timer B Compare 4 + 24 + 1 + + + TIMBCMP2 + Timer B Compare 2 + 23 + 1 + + + TIMBCMP1 + Timer B Compare 1 + 22 + 1 + + + TIMACMP4 + Timer A Compare 4 + 21 + 1 + + + TIMACMP2 + Timer A Compare 2 + 20 + 1 + + + TIMACMP1 + Timer A Compare 1 + 19 + 1 + + + EXTEVNT10 + External Event 10 + 18 + 1 + + + EXTEVNT9 + External Event 9 + 17 + 1 + + + EXTEVNT8 + External Event 8 + 16 + 1 + + + EXTEVNT7 + External Event 7 + 15 + 1 + + + EXTEVNT6 + External Event 6 + 14 + 1 + + + EXTEVNT5 + External Event 5 + 13 + 1 + + + EXTEVNT4 + External Event 4 + 12 + 1 + + + EXTEVNT3 + External Event 3 + 11 + 1 + + + EXTEVNT2 + External Event 2 + 10 + 1 + + + EXTEVNT1 + External Event 1 + 9 + 1 + + + MSTCMP4 + Master compare 4 + 8 + 1 + + + MSTCMP3 + Master compare 3 + 7 + 1 + + + MSTCMP2 + Master compare 2 + 6 + 1 + + + MSTCMP1 + Master compare 1 + 5 + 1 + + + MSTPER + Master timer Period + 4 + 1 + + + CMP4 + Timer A compare 4 reset + 3 + 1 + + + CMP2 + Timer A compare 2 reset + 2 + 1 + + + UPDT + Timer A Update reset + 1 + 1 + + + + + CHPCR + CHPCR + Timerx Chopper Register + 0x58 + 0x20 + read-write + 0x00000000 + + + STRTPW + STRTPW + 7 + 4 + + + CHPDTY + Timerx chopper duty cycle + value + 4 + 3 + + + CHPFRQ + Timerx carrier frequency + value + 0 + 4 + + + + + CPT1CCR + CPT1CCR + Timerx Capture 2 Control + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + CPT2CCR + CPT2CCR + CPT2xCR + 0x60 + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + OUTCR + OUTCR + Timerx Output Register + 0x64 + 0x20 + read-write + 0x00000000 + + + DIDL2 + Output 2 Deadtime upon burst mode Idle + entry + 23 + 1 + + + CHP2 + Output 2 Chopper enable + 22 + 1 + + + FAULT2 + Output 2 Fault state + 20 + 2 + + + IDLES2 + Output 2 Idle State + 19 + 1 + + + IDLEM2 + Output 2 Idle mode + 18 + 1 + + + POL2 + Output 2 polarity + 17 + 1 + + + DLYPRT + Delayed Protection + 10 + 3 + + + DLYPRTEN + Delayed Protection Enable + 9 + 1 + + + DTEN + Deadtime enable + 8 + 1 + + + DIDL1 + Output 1 Deadtime upon burst mode Idle + entry + 7 + 1 + + + CHP1 + Output 1 Chopper enable + 6 + 1 + + + FAULT1 + Output 1 Fault state + 4 + 2 + + + IDLES1 + Output 1 Idle State + 3 + 1 + + + IDLEM1 + Output 1 Idle mode + 2 + 1 + + + POL1 + Output 1 polarity + 1 + 1 + + + + + FLTCR + FLTCR + Timerx Fault Register + 0x68 + 0x20 + read-write + 0x00000000 + + + FLTLCK + Fault sources Lock + 31 + 1 + + + FLT5EN + Fault 5 enable + 4 + 1 + + + FLT4EN + Fault 4 enable + 3 + 1 + + + FLT3EN + Fault 3 enable + 2 + 1 + + + FLT2EN + Fault 2 enable + 1 + 1 + + + FLT1EN + Fault 1 enable + 0 + 1 + + + + + + + HRTIM_TIMD + High Resolution Timer: TIMD + HRTIM + 0x40017600 + + 0x0 + 0x80 + registers + + + HRTIM1_TIMC + HRTIM1 timer C interrupt + 106 + + + + TIMDCR + TIMDCR + Timerx Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + UPDGAT + Update Gating + 28 + 4 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + MSTU + Master Timer update + 24 + 1 + + + TEU + TEU + 23 + 1 + + + TDU + TDU + 22 + 1 + + + TCU + TCU + 21 + 1 + + + TBU + TBU + 20 + 1 + + + TxRSTU + Timerx reset update + 18 + 1 + + + TxREPU + Timer x Repetition update + 17 + 1 + + + DELCMP4 + Delayed CMP4 mode + 14 + 2 + + + DELCMP2 + Delayed CMP2 mode + 12 + 2 + + + SYNCSTRTx + Synchronization Starts Timer + x + 11 + 1 + + + SYNCRSTx + Synchronization Resets Timer + x + 10 + 1 + + + PSHPLL + Push-Pull mode enable + 6 + 1 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Re-triggerable mode + 4 + 1 + + + CONT + Continuous mode + 3 + 1 + + + CK_PSCx + HRTIM Timer x Clock + prescaler + 0 + 3 + + + + + TIMDISR + TIMDISR + Timerx Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + O2STAT + Output 2 State + 19 + 1 + + + O1STAT + Output 1 State + 18 + 1 + + + IPPSTAT + Idle Push Pull Status + 17 + 1 + + + CPPSTAT + Current Push Pull Status + 16 + 1 + + + DLYPRT + Delayed Protection Flag + 14 + 1 + + + RST + Reset Interrupt Flag + 13 + 1 + + + RSTx2 + Output 2 Reset Interrupt + Flag + 12 + 1 + + + SETx2 + Output 2 Set Interrupt + Flag + 11 + 1 + + + RSTx1 + Output 1 Reset Interrupt + Flag + 10 + 1 + + + SETx1 + Output 1 Set Interrupt + Flag + 9 + 1 + + + CPT2 + Capture2 Interrupt Flag + 8 + 1 + + + CPT1 + Capture1 Interrupt Flag + 7 + 1 + + + UPD + Update Interrupt Flag + 6 + 1 + + + REP + Repetition Interrupt Flag + 4 + 1 + + + CMP4 + Compare 4 Interrupt Flag + 3 + 1 + + + CMP3 + Compare 3 Interrupt Flag + 2 + 1 + + + CMP2 + Compare 2 Interrupt Flag + 1 + 1 + + + CMP1 + Compare 1 Interrupt Flag + 0 + 1 + + + + + TIMDICR + TIMDICR + Timerx Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + DLYPRTC + Delayed Protection Flag + Clear + 14 + 1 + + + RSTC + Reset Interrupt flag Clear + 13 + 1 + + + RSTx2C + Output 2 Reset flag Clear + 12 + 1 + + + SET2xC + Output 2 Set flag Clear + 11 + 1 + + + RSTx1C + Output 1 Reset flag Clear + 10 + 1 + + + SET1xC + Output 1 Set flag Clear + 9 + 1 + + + CPT2C + Capture2 Interrupt flag + Clear + 8 + 1 + + + CPT1C + Capture1 Interrupt flag + Clear + 7 + 1 + + + UPDC + Update Interrupt flag + Clear + 6 + 1 + + + REPC + Repetition Interrupt flag + Clear + 4 + 1 + + + CMP4C + Compare 4 Interrupt flag + Clear + 3 + 1 + + + CMP3C + Compare 3 Interrupt flag + Clear + 2 + 1 + + + CMP2C + Compare 2 Interrupt flag + Clear + 1 + 1 + + + CMP1C + Compare 1 Interrupt flag + Clear + 0 + 1 + + + + + TIMDDIER5 + TIMDDIER5 + TIMxDIER5 + 0xC + 0x20 + read-write + 0x00000000 + + + DLYPRTDE + DLYPRTDE + 30 + 1 + + + RSTDE + RSTDE + 29 + 1 + + + RSTx2DE + RSTx2DE + 28 + 1 + + + SETx2DE + SETx2DE + 27 + 1 + + + RSTx1DE + RSTx1DE + 26 + 1 + + + SET1xDE + SET1xDE + 25 + 1 + + + CPT2DE + CPT2DE + 24 + 1 + + + CPT1DE + CPT1DE + 23 + 1 + + + UPDDE + UPDDE + 22 + 1 + + + REPDE + REPDE + 20 + 1 + + + CMP4DE + CMP4DE + 19 + 1 + + + CMP3DE + CMP3DE + 18 + 1 + + + CMP2DE + CMP2DE + 17 + 1 + + + CMP1DE + CMP1DE + 16 + 1 + + + DLYPRTIE + DLYPRTIE + 14 + 1 + + + RSTIE + RSTIE + 13 + 1 + + + RSTx2IE + RSTx2IE + 12 + 1 + + + SETx2IE + SETx2IE + 11 + 1 + + + RSTx1IE + RSTx1IE + 10 + 1 + + + SET1xIE + SET1xIE + 9 + 1 + + + CPT2IE + CPT2IE + 8 + 1 + + + CPT1IE + CPT1IE + 7 + 1 + + + UPDIE + UPDIE + 6 + 1 + + + REPIE + REPIE + 4 + 1 + + + CMP4IE + CMP4IE + 3 + 1 + + + CMP3IE + CMP3IE + 2 + 1 + + + CMP2IE + CMP2IE + 1 + 1 + + + CMP1IE + CMP1IE + 0 + 1 + + + + + CNTDR + CNTDR + Timerx Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTx + Timerx Counter value + 0 + 16 + + + + + PERDR + PERDR + Timerx Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + PERx + Timerx Period value + 0 + 16 + + + + + REPDR + REPDR + Timerx Repetition Register + 0x18 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition counter + value + 0 + 8 + + + + + CMP1DR + CMP1DR + Timerx Compare 1 Register + 0x1C + 0x20 + read-write + 0x00000000 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP1CDR + CMP1CDR + Timerx Compare 1 Compound + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition value (aliased from + HRTIM_REPx register) + 16 + 8 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP2DR + CMP2DR + Timerx Compare 2 Register + 0x24 + 0x20 + read-write + 0x00000000 + + + CMP2x + Timerx Compare 2 value + 0 + 16 + + + + + CMP3DR + CMP3DR + Timerx Compare 3 Register + 0x28 + 0x20 + read-write + 0x00000000 + + + CMP3x + Timerx Compare 3 value + 0 + 16 + + + + + CMP4DR + CMP4DR + Timerx Compare 4 Register + 0x2C + 0x20 + read-write + 0x00000000 + + + CMP4x + Timerx Compare 4 value + 0 + 16 + + + + + CPT1DR + CPT1DR + Timerx Capture 1 Register + 0x30 + 0x20 + read-only + 0x00000000 + + + CPT1x + Timerx Capture 1 value + 0 + 16 + + + + + CPT2DR + CPT2DR + Timerx Capture 2 Register + 0x34 + 0x20 + read-only + 0x00000000 + + + CPT2x + Timerx Capture 2 value + 0 + 16 + + + + + DTDR + DTDR + Timerx Deadtime Register + 0x38 + 0x20 + read-write + 0x00000000 + + + DTFLKx + Deadtime Falling Lock + 31 + 1 + + + DTFSLKx + Deadtime Falling Sign Lock + 30 + 1 + + + SDTFx + Sign Deadtime Falling + value + 25 + 1 + + + DTFx + Deadtime Falling value + 16 + 9 + + + DTRLKx + Deadtime Rising Lock + 15 + 1 + + + DTRSLKx + Deadtime Rising Sign Lock + 14 + 1 + + + DTPRSC + Deadtime Prescaler + 10 + 3 + + + SDTRx + Sign Deadtime Rising value + 9 + 1 + + + DTRx + Deadtime Rising value + 0 + 9 + + + + + SETD1R + SETD1R + Timerx Output1 Set Register + 0x3C + 0x20 + read-write + 0x00000000 + + + UPDATE + Registers update (transfer preload to + active) + 31 + 1 + + + EXTEVNT10 + External Event 10 + 30 + 1 + + + EXTEVNT9 + External Event 9 + 29 + 1 + + + EXTEVNT8 + External Event 8 + 28 + 1 + + + EXTEVNT7 + External Event 7 + 27 + 1 + + + EXTEVNT6 + External Event 6 + 26 + 1 + + + EXTEVNT5 + External Event 5 + 25 + 1 + + + EXTEVNT4 + External Event 4 + 24 + 1 + + + EXTEVNT3 + External Event 3 + 23 + 1 + + + EXTEVNT2 + External Event 2 + 22 + 1 + + + EXTEVNT1 + External Event 1 + 21 + 1 + + + TIMEVNT9 + Timer Event 9 + 20 + 1 + + + TIMEVNT8 + Timer Event 8 + 19 + 1 + + + TIMEVNT7 + Timer Event 7 + 18 + 1 + + + TIMEVNT6 + Timer Event 6 + 17 + 1 + + + TIMEVNT5 + Timer Event 5 + 16 + 1 + + + TIMEVNT4 + Timer Event 4 + 15 + 1 + + + TIMEVNT3 + Timer Event 3 + 14 + 1 + + + TIMEVNT2 + Timer Event 2 + 13 + 1 + + + TIMEVNT1 + Timer Event 1 + 12 + 1 + + + MSTCMP4 + Master Compare 4 + 11 + 1 + + + MSTCMP3 + Master Compare 3 + 10 + 1 + + + MSTCMP2 + Master Compare 2 + 9 + 1 + + + MSTCMP1 + Master Compare 1 + 8 + 1 + + + MSTPER + Master Period + 7 + 1 + + + CMP4 + Timer A compare 4 + 6 + 1 + + + CMP3 + Timer A compare 3 + 5 + 1 + + + CMP2 + Timer A compare 2 + 4 + 1 + + + CMP1 + Timer A compare 1 + 3 + 1 + + + PER + Timer A Period + 2 + 1 + + + RESYNC + Timer A resynchronizaton + 1 + 1 + + + SST + Software Set trigger + 0 + 1 + + + + + RSTD1R + RSTD1R + Timerx Output1 Reset Register + 0x40 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + SETD2R + SETD2R + Timerx Output2 Set Register + 0x44 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SST + SST + 0 + 1 + + + + + RSTD2R + RSTD2R + Timerx Output2 Reset Register + 0x48 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + EEFDR1 + EEFDR1 + Timerx External Event Filtering Register + 1 + 0x4C + 0x20 + read-write + 0x00000000 + + + EE5FLTR + External Event 5 filter + 25 + 4 + + + EE5LTCH + External Event 5 latch + 24 + 1 + + + EE4FLTR + External Event 4 filter + 19 + 4 + + + EE4LTCH + External Event 4 latch + 18 + 1 + + + EE3FLTR + External Event 3 filter + 13 + 4 + + + EE3LTCH + External Event 3 latch + 12 + 1 + + + EE2FLTR + External Event 2 filter + 7 + 4 + + + EE2LTCH + External Event 2 latch + 6 + 1 + + + EE1FLTR + External Event 1 filter + 1 + 4 + + + EE1LTCH + External Event 1 latch + 0 + 1 + + + + + EEFDR2 + EEFDR2 + Timerx External Event Filtering Register + 2 + 0x50 + 0x20 + read-write + 0x00000000 + + + EE10FLTR + External Event 10 filter + 25 + 4 + + + EE10LTCH + External Event 10 latch + 24 + 1 + + + EE9FLTR + External Event 9 filter + 19 + 4 + + + EE9LTCH + External Event 9 latch + 18 + 1 + + + EE8FLTR + External Event 8 filter + 13 + 4 + + + EE8LTCH + External Event 8 latch + 12 + 1 + + + EE7FLTR + External Event 7 filter + 7 + 4 + + + EE7LTCH + External Event 7 latch + 6 + 1 + + + EE6FLTR + External Event 6 filter + 1 + 4 + + + EE6LTCH + External Event 6 latch + 0 + 1 + + + + + RSTDR + RSTDR + TimerA Reset Register + 0x54 + 0x20 + read-write + 0x00000000 + + + TIMECMP4 + Timer E Compare 4 + 30 + 1 + + + TIMECMP2 + Timer E Compare 2 + 29 + 1 + + + TIMECMP1 + Timer E Compare 1 + 28 + 1 + + + TIMCCMP4 + Timer C Compare 4 + 27 + 1 + + + TIMCCMP2 + Timer C Compare 2 + 26 + 1 + + + TIMCCMP1 + Timer C Compare 1 + 25 + 1 + + + TIMBCMP4 + Timer B Compare 4 + 24 + 1 + + + TIMBCMP2 + Timer B Compare 2 + 23 + 1 + + + TIMBCMP1 + Timer B Compare 1 + 22 + 1 + + + TIMACMP4 + Timer A Compare 4 + 21 + 1 + + + TIMACMP2 + Timer A Compare 2 + 20 + 1 + + + TIMACMP1 + Timer A Compare 1 + 19 + 1 + + + EXTEVNT10 + External Event 10 + 18 + 1 + + + EXTEVNT9 + External Event 9 + 17 + 1 + + + EXTEVNT8 + External Event 8 + 16 + 1 + + + EXTEVNT7 + External Event 7 + 15 + 1 + + + EXTEVNT6 + External Event 6 + 14 + 1 + + + EXTEVNT5 + External Event 5 + 13 + 1 + + + EXTEVNT4 + External Event 4 + 12 + 1 + + + EXTEVNT3 + External Event 3 + 11 + 1 + + + EXTEVNT2 + External Event 2 + 10 + 1 + + + EXTEVNT1 + External Event 1 + 9 + 1 + + + MSTCMP4 + Master compare 4 + 8 + 1 + + + MSTCMP3 + Master compare 3 + 7 + 1 + + + MSTCMP2 + Master compare 2 + 6 + 1 + + + MSTCMP1 + Master compare 1 + 5 + 1 + + + MSTPER + Master timer Period + 4 + 1 + + + CMP4 + Timer A compare 4 reset + 3 + 1 + + + CMP2 + Timer A compare 2 reset + 2 + 1 + + + UPDT + Timer A Update reset + 1 + 1 + + + + + CHPDR + CHPDR + Timerx Chopper Register + 0x58 + 0x20 + read-write + 0x00000000 + + + STRTPW + STRTPW + 7 + 4 + + + CHPDTY + Timerx chopper duty cycle + value + 4 + 3 + + + CHPFRQ + Timerx carrier frequency + value + 0 + 4 + + + + + CPT1DCR + CPT1DCR + Timerx Capture 2 Control + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + CPT2DCR + CPT2DCR + CPT2xCR + 0x60 + 0x20 + read-write + 0x00000000 + + + TECMP2 + Timer E Compare 2 + 31 + 1 + + + TECMP1 + Timer E Compare 1 + 30 + 1 + + + TE1RST + Timer E output 1 Reset + 29 + 1 + + + TE1SET + Timer E output 1 Set + 28 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + OUTDR + OUTDR + Timerx Output Register + 0x64 + 0x20 + read-write + 0x00000000 + + + DIDL2 + Output 2 Deadtime upon burst mode Idle + entry + 23 + 1 + + + CHP2 + Output 2 Chopper enable + 22 + 1 + + + FAULT2 + Output 2 Fault state + 20 + 2 + + + IDLES2 + Output 2 Idle State + 19 + 1 + + + IDLEM2 + Output 2 Idle mode + 18 + 1 + + + POL2 + Output 2 polarity + 17 + 1 + + + DLYPRT + Delayed Protection + 10 + 3 + + + DLYPRTEN + Delayed Protection Enable + 9 + 1 + + + DTEN + Deadtime enable + 8 + 1 + + + DIDL1 + Output 1 Deadtime upon burst mode Idle + entry + 7 + 1 + + + CHP1 + Output 1 Chopper enable + 6 + 1 + + + FAULT1 + Output 1 Fault state + 4 + 2 + + + IDLES1 + Output 1 Idle State + 3 + 1 + + + IDLEM1 + Output 1 Idle mode + 2 + 1 + + + POL1 + Output 1 polarity + 1 + 1 + + + + + FLTDR + FLTDR + Timerx Fault Register + 0x68 + 0x20 + read-write + 0x00000000 + + + FLTLCK + Fault sources Lock + 31 + 1 + + + FLT5EN + Fault 5 enable + 4 + 1 + + + FLT4EN + Fault 4 enable + 3 + 1 + + + FLT3EN + Fault 3 enable + 2 + 1 + + + FLT2EN + Fault 2 enable + 1 + 1 + + + FLT1EN + Fault 1 enable + 0 + 1 + + + + + + + HRTIM_TIME + High Resolution Timer: TIME + HRTIM + 0x40017680 + + 0x0 + 0x80 + registers + + + HRTIM1_TIMD + HRTIM1 timer D interrupt + 107 + + + + TIMECR + TIMECR + Timerx Control Register + 0x0 + 0x20 + read-write + 0x00000000 + + + UPDGAT + Update Gating + 28 + 4 + + + PREEN + Preload enable + 27 + 1 + + + DACSYNC + AC Synchronization + 25 + 2 + + + MSTU + Master Timer update + 24 + 1 + + + TEU + TEU + 23 + 1 + + + TDU + TDU + 22 + 1 + + + TCU + TCU + 21 + 1 + + + TBU + TBU + 20 + 1 + + + TxRSTU + Timerx reset update + 18 + 1 + + + TxREPU + Timer x Repetition update + 17 + 1 + + + DELCMP4 + Delayed CMP4 mode + 14 + 2 + + + DELCMP2 + Delayed CMP2 mode + 12 + 2 + + + SYNCSTRTx + Synchronization Starts Timer + x + 11 + 1 + + + SYNCRSTx + Synchronization Resets Timer + x + 10 + 1 + + + PSHPLL + Push-Pull mode enable + 6 + 1 + + + HALF + Half mode enable + 5 + 1 + + + RETRIG + Re-triggerable mode + 4 + 1 + + + CONT + Continuous mode + 3 + 1 + + + CK_PSCx + HRTIM Timer x Clock + prescaler + 0 + 3 + + + + + TIMEISR + TIMEISR + Timerx Interrupt Status + Register + 0x4 + 0x20 + read-only + 0x00000000 + + + O2STAT + Output 2 State + 19 + 1 + + + O1STAT + Output 1 State + 18 + 1 + + + IPPSTAT + Idle Push Pull Status + 17 + 1 + + + CPPSTAT + Current Push Pull Status + 16 + 1 + + + DLYPRT + Delayed Protection Flag + 14 + 1 + + + RST + Reset Interrupt Flag + 13 + 1 + + + RSTx2 + Output 2 Reset Interrupt + Flag + 12 + 1 + + + SETx2 + Output 2 Set Interrupt + Flag + 11 + 1 + + + RSTx1 + Output 1 Reset Interrupt + Flag + 10 + 1 + + + SETx1 + Output 1 Set Interrupt + Flag + 9 + 1 + + + CPT2 + Capture2 Interrupt Flag + 8 + 1 + + + CPT1 + Capture1 Interrupt Flag + 7 + 1 + + + UPD + Update Interrupt Flag + 6 + 1 + + + REP + Repetition Interrupt Flag + 4 + 1 + + + CMP4 + Compare 4 Interrupt Flag + 3 + 1 + + + CMP3 + Compare 3 Interrupt Flag + 2 + 1 + + + CMP2 + Compare 2 Interrupt Flag + 1 + 1 + + + CMP1 + Compare 1 Interrupt Flag + 0 + 1 + + + + + TIMEICR + TIMEICR + Timerx Interrupt Clear + Register + 0x8 + 0x20 + write-only + 0x00000000 + + + DLYPRTC + Delayed Protection Flag + Clear + 14 + 1 + + + RSTC + Reset Interrupt flag Clear + 13 + 1 + + + RSTx2C + Output 2 Reset flag Clear + 12 + 1 + + + SET2xC + Output 2 Set flag Clear + 11 + 1 + + + RSTx1C + Output 1 Reset flag Clear + 10 + 1 + + + SET1xC + Output 1 Set flag Clear + 9 + 1 + + + CPT2C + Capture2 Interrupt flag + Clear + 8 + 1 + + + CPT1C + Capture1 Interrupt flag + Clear + 7 + 1 + + + UPDC + Update Interrupt flag + Clear + 6 + 1 + + + REPC + Repetition Interrupt flag + Clear + 4 + 1 + + + CMP4C + Compare 4 Interrupt flag + Clear + 3 + 1 + + + CMP3C + Compare 3 Interrupt flag + Clear + 2 + 1 + + + CMP2C + Compare 2 Interrupt flag + Clear + 1 + 1 + + + CMP1C + Compare 1 Interrupt flag + Clear + 0 + 1 + + + + + TIMEDIER5 + TIMEDIER5 + TIMxDIER5 + 0xC + 0x20 + read-write + 0x00000000 + + + DLYPRTDE + DLYPRTDE + 30 + 1 + + + RSTDE + RSTDE + 29 + 1 + + + RSTx2DE + RSTx2DE + 28 + 1 + + + SETx2DE + SETx2DE + 27 + 1 + + + RSTx1DE + RSTx1DE + 26 + 1 + + + SET1xDE + SET1xDE + 25 + 1 + + + CPT2DE + CPT2DE + 24 + 1 + + + CPT1DE + CPT1DE + 23 + 1 + + + UPDDE + UPDDE + 22 + 1 + + + REPDE + REPDE + 20 + 1 + + + CMP4DE + CMP4DE + 19 + 1 + + + CMP3DE + CMP3DE + 18 + 1 + + + CMP2DE + CMP2DE + 17 + 1 + + + CMP1DE + CMP1DE + 16 + 1 + + + DLYPRTIE + DLYPRTIE + 14 + 1 + + + RSTIE + RSTIE + 13 + 1 + + + RSTx2IE + RSTx2IE + 12 + 1 + + + SETx2IE + SETx2IE + 11 + 1 + + + RSTx1IE + RSTx1IE + 10 + 1 + + + SET1xIE + SET1xIE + 9 + 1 + + + CPT2IE + CPT2IE + 8 + 1 + + + CPT1IE + CPT1IE + 7 + 1 + + + UPDIE + UPDIE + 6 + 1 + + + REPIE + REPIE + 4 + 1 + + + CMP4IE + CMP4IE + 3 + 1 + + + CMP3IE + CMP3IE + 2 + 1 + + + CMP2IE + CMP2IE + 1 + 1 + + + CMP1IE + CMP1IE + 0 + 1 + + + + + CNTER + CNTER + Timerx Counter Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CNTx + Timerx Counter value + 0 + 16 + + + + + PERER + PERER + Timerx Period Register + 0x14 + 0x20 + read-write + 0x0000FFFF + + + PERx + Timerx Period value + 0 + 16 + + + + + REPER + REPER + Timerx Repetition Register + 0x18 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition counter + value + 0 + 8 + + + + + CMP1ER + CMP1ER + Timerx Compare 1 Register + 0x1C + 0x20 + read-write + 0x00000000 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP1CER + CMP1CER + Timerx Compare 1 Compound + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + REPx + Timerx Repetition value (aliased from + HRTIM_REPx register) + 16 + 8 + + + CMP1x + Timerx Compare 1 value + 0 + 16 + + + + + CMP2ER + CMP2ER + Timerx Compare 2 Register + 0x24 + 0x20 + read-write + 0x00000000 + + + CMP2x + Timerx Compare 2 value + 0 + 16 + + + + + CMP3ER + CMP3ER + Timerx Compare 3 Register + 0x28 + 0x20 + read-write + 0x00000000 + + + CMP3x + Timerx Compare 3 value + 0 + 16 + + + + + CMP4ER + CMP4ER + Timerx Compare 4 Register + 0x2C + 0x20 + read-write + 0x00000000 + + + CMP4x + Timerx Compare 4 value + 0 + 16 + + + + + CPT1ER + CPT1ER + Timerx Capture 1 Register + 0x30 + 0x20 + read-only + 0x00000000 + + + CPT1x + Timerx Capture 1 value + 0 + 16 + + + + + CPT2ER + CPT2ER + Timerx Capture 2 Register + 0x34 + 0x20 + read-only + 0x00000000 + + + CPT2x + Timerx Capture 2 value + 0 + 16 + + + + + DTER + DTER + Timerx Deadtime Register + 0x38 + 0x20 + read-write + 0x00000000 + + + DTFLKx + Deadtime Falling Lock + 31 + 1 + + + DTFSLKx + Deadtime Falling Sign Lock + 30 + 1 + + + SDTFx + Sign Deadtime Falling + value + 25 + 1 + + + DTFx + Deadtime Falling value + 16 + 9 + + + DTRLKx + Deadtime Rising Lock + 15 + 1 + + + DTRSLKx + Deadtime Rising Sign Lock + 14 + 1 + + + DTPRSC + Deadtime Prescaler + 10 + 3 + + + SDTRx + Sign Deadtime Rising value + 9 + 1 + + + DTRx + Deadtime Rising value + 0 + 9 + + + + + SETE1R + SETE1R + Timerx Output1 Set Register + 0x3C + 0x20 + read-write + 0x00000000 + + + UPDATE + Registers update (transfer preload to + active) + 31 + 1 + + + EXTEVNT10 + External Event 10 + 30 + 1 + + + EXTEVNT9 + External Event 9 + 29 + 1 + + + EXTEVNT8 + External Event 8 + 28 + 1 + + + EXTEVNT7 + External Event 7 + 27 + 1 + + + EXTEVNT6 + External Event 6 + 26 + 1 + + + EXTEVNT5 + External Event 5 + 25 + 1 + + + EXTEVNT4 + External Event 4 + 24 + 1 + + + EXTEVNT3 + External Event 3 + 23 + 1 + + + EXTEVNT2 + External Event 2 + 22 + 1 + + + EXTEVNT1 + External Event 1 + 21 + 1 + + + TIMEVNT9 + Timer Event 9 + 20 + 1 + + + TIMEVNT8 + Timer Event 8 + 19 + 1 + + + TIMEVNT7 + Timer Event 7 + 18 + 1 + + + TIMEVNT6 + Timer Event 6 + 17 + 1 + + + TIMEVNT5 + Timer Event 5 + 16 + 1 + + + TIMEVNT4 + Timer Event 4 + 15 + 1 + + + TIMEVNT3 + Timer Event 3 + 14 + 1 + + + TIMEVNT2 + Timer Event 2 + 13 + 1 + + + TIMEVNT1 + Timer Event 1 + 12 + 1 + + + MSTCMP4 + Master Compare 4 + 11 + 1 + + + MSTCMP3 + Master Compare 3 + 10 + 1 + + + MSTCMP2 + Master Compare 2 + 9 + 1 + + + MSTCMP1 + Master Compare 1 + 8 + 1 + + + MSTPER + Master Period + 7 + 1 + + + CMP4 + Timer A compare 4 + 6 + 1 + + + CMP3 + Timer A compare 3 + 5 + 1 + + + CMP2 + Timer A compare 2 + 4 + 1 + + + CMP1 + Timer A compare 1 + 3 + 1 + + + PER + Timer A Period + 2 + 1 + + + RESYNC + Timer A resynchronizaton + 1 + 1 + + + SST + Software Set trigger + 0 + 1 + + + + + RSTE1R + RSTE1R + Timerx Output1 Reset Register + 0x40 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + SETE2R + SETE2R + Timerx Output2 Set Register + 0x44 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SST + SST + 0 + 1 + + + + + RSTE2R + RSTE2R + Timerx Output2 Reset Register + 0x48 + 0x20 + read-write + 0x00000000 + + + UPDATE + UPDATE + 31 + 1 + + + EXTEVNT10 + EXTEVNT10 + 30 + 1 + + + EXTEVNT9 + EXTEVNT9 + 29 + 1 + + + EXTEVNT8 + EXTEVNT8 + 28 + 1 + + + EXTEVNT7 + EXTEVNT7 + 27 + 1 + + + EXTEVNT6 + EXTEVNT6 + 26 + 1 + + + EXTEVNT5 + EXTEVNT5 + 25 + 1 + + + EXTEVNT4 + EXTEVNT4 + 24 + 1 + + + EXTEVNT3 + EXTEVNT3 + 23 + 1 + + + EXTEVNT2 + EXTEVNT2 + 22 + 1 + + + EXTEVNT1 + EXTEVNT1 + 21 + 1 + + + TIMEVNT9 + TIMEVNT9 + 20 + 1 + + + TIMEVNT8 + TIMEVNT8 + 19 + 1 + + + TIMEVNT7 + TIMEVNT7 + 18 + 1 + + + TIMEVNT6 + TIMEVNT6 + 17 + 1 + + + TIMEVNT5 + TIMEVNT5 + 16 + 1 + + + TIMEVNT4 + TIMEVNT4 + 15 + 1 + + + TIMEVNT3 + TIMEVNT3 + 14 + 1 + + + TIMEVNT2 + TIMEVNT2 + 13 + 1 + + + TIMEVNT1 + TIMEVNT1 + 12 + 1 + + + MSTCMP4 + MSTCMP4 + 11 + 1 + + + MSTCMP3 + MSTCMP3 + 10 + 1 + + + MSTCMP2 + MSTCMP2 + 9 + 1 + + + MSTCMP1 + MSTCMP1 + 8 + 1 + + + MSTPER + MSTPER + 7 + 1 + + + CMP4 + CMP4 + 6 + 1 + + + CMP3 + CMP3 + 5 + 1 + + + CMP2 + CMP2 + 4 + 1 + + + CMP1 + CMP1 + 3 + 1 + + + PER + PER + 2 + 1 + + + RESYNC + RESYNC + 1 + 1 + + + SRT + SRT + 0 + 1 + + + + + EEFER1 + EEFER1 + Timerx External Event Filtering Register + 1 + 0x4C + 0x20 + read-write + 0x00000000 + + + EE5FLTR + External Event 5 filter + 25 + 4 + + + EE5LTCH + External Event 5 latch + 24 + 1 + + + EE4FLTR + External Event 4 filter + 19 + 4 + + + EE4LTCH + External Event 4 latch + 18 + 1 + + + EE3FLTR + External Event 3 filter + 13 + 4 + + + EE3LTCH + External Event 3 latch + 12 + 1 + + + EE2FLTR + External Event 2 filter + 7 + 4 + + + EE2LTCH + External Event 2 latch + 6 + 1 + + + EE1FLTR + External Event 1 filter + 1 + 4 + + + EE1LTCH + External Event 1 latch + 0 + 1 + + + + + EEFER2 + EEFER2 + Timerx External Event Filtering Register + 2 + 0x50 + 0x20 + read-write + 0x00000000 + + + EE10FLTR + External Event 10 filter + 25 + 4 + + + EE10LTCH + External Event 10 latch + 24 + 1 + + + EE9FLTR + External Event 9 filter + 19 + 4 + + + EE9LTCH + External Event 9 latch + 18 + 1 + + + EE8FLTR + External Event 8 filter + 13 + 4 + + + EE8LTCH + External Event 8 latch + 12 + 1 + + + EE7FLTR + External Event 7 filter + 7 + 4 + + + EE7LTCH + External Event 7 latch + 6 + 1 + + + EE6FLTR + External Event 6 filter + 1 + 4 + + + EE6LTCH + External Event 6 latch + 0 + 1 + + + + + RSTER + RSTER + TimerA Reset Register + 0x54 + 0x20 + read-write + 0x00000000 + + + TIMDCMP4 + Timer D Compare 4 + 30 + 1 + + + TIMDCMP2 + Timer D Compare 2 + 29 + 1 + + + TIMDCMP1 + Timer D Compare 1 + 28 + 1 + + + TIMCCMP4 + Timer C Compare 4 + 27 + 1 + + + TIMCCMP2 + Timer C Compare 2 + 26 + 1 + + + TIMCCMP1 + Timer C Compare 1 + 25 + 1 + + + TIMBCMP4 + Timer B Compare 4 + 24 + 1 + + + TIMBCMP2 + Timer B Compare 2 + 23 + 1 + + + TIMBCMP1 + Timer B Compare 1 + 22 + 1 + + + TIMACMP4 + Timer A Compare 4 + 21 + 1 + + + TIMACMP2 + Timer A Compare 2 + 20 + 1 + + + TIMACMP1 + Timer A Compare 1 + 19 + 1 + + + EXTEVNT10 + External Event 10 + 18 + 1 + + + EXTEVNT9 + External Event 9 + 17 + 1 + + + EXTEVNT8 + External Event 8 + 16 + 1 + + + EXTEVNT7 + External Event 7 + 15 + 1 + + + EXTEVNT6 + External Event 6 + 14 + 1 + + + EXTEVNT5 + External Event 5 + 13 + 1 + + + EXTEVNT4 + External Event 4 + 12 + 1 + + + EXTEVNT3 + External Event 3 + 11 + 1 + + + EXTEVNT2 + External Event 2 + 10 + 1 + + + EXTEVNT1 + External Event 1 + 9 + 1 + + + MSTCMP4 + Master compare 4 + 8 + 1 + + + MSTCMP3 + Master compare 3 + 7 + 1 + + + MSTCMP2 + Master compare 2 + 6 + 1 + + + MSTCMP1 + Master compare 1 + 5 + 1 + + + MSTPER + Master timer Period + 4 + 1 + + + CMP4 + Timer A compare 4 reset + 3 + 1 + + + CMP2 + Timer A compare 2 reset + 2 + 1 + + + UPDT + Timer A Update reset + 1 + 1 + + + + + CHPER + CHPER + Timerx Chopper Register + 0x58 + 0x20 + read-write + 0x00000000 + + + STRTPW + STRTPW + 7 + 4 + + + CHPDTY + Timerx chopper duty cycle + value + 4 + 3 + + + CHPFRQ + Timerx carrier frequency + value + 0 + 4 + + + + + CPT1ECR + CPT1ECR + Timerx Capture 2 Control + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + CPT2ECR + CPT2ECR + CPT2xCR + 0x60 + 0x20 + read-write + 0x00000000 + + + TDCMP2 + Timer D Compare 2 + 27 + 1 + + + TDCMP1 + Timer D Compare 1 + 26 + 1 + + + TD1RST + Timer D output 1 Reset + 25 + 1 + + + TD1SET + Timer D output 1 Set + 24 + 1 + + + TCCMP2 + Timer C Compare 2 + 23 + 1 + + + TCCMP1 + Timer C Compare 1 + 22 + 1 + + + TC1RST + Timer C output 1 Reset + 21 + 1 + + + TC1SET + Timer C output 1 Set + 20 + 1 + + + TBCMP2 + Timer B Compare 2 + 19 + 1 + + + TBCMP1 + Timer B Compare 1 + 18 + 1 + + + TB1RST + Timer B output 1 Reset + 17 + 1 + + + TB1SET + Timer B output 1 Set + 16 + 1 + + + TACMP2 + Timer A Compare 2 + 15 + 1 + + + TACMP1 + Timer A Compare 1 + 14 + 1 + + + TA1RST + Timer A output 1 Reset + 13 + 1 + + + TA1SET + Timer A output 1 Set + 12 + 1 + + + EXEV10CPT + External Event 10 Capture + 11 + 1 + + + EXEV9CPT + External Event 9 Capture + 10 + 1 + + + EXEV8CPT + External Event 8 Capture + 9 + 1 + + + EXEV7CPT + External Event 7 Capture + 8 + 1 + + + EXEV6CPT + External Event 6 Capture + 7 + 1 + + + EXEV5CPT + External Event 5 Capture + 6 + 1 + + + EXEV4CPT + External Event 4 Capture + 5 + 1 + + + EXEV3CPT + External Event 3 Capture + 4 + 1 + + + EXEV2CPT + External Event 2 Capture + 3 + 1 + + + EXEV1CPT + External Event 1 Capture + 2 + 1 + + + UDPCPT + Update Capture + 1 + 1 + + + SWCPT + Software Capture + 0 + 1 + + + + + OUTER + OUTER + Timerx Output Register + 0x64 + 0x20 + read-write + 0x00000000 + + + DIDL2 + Output 2 Deadtime upon burst mode Idle + entry + 23 + 1 + + + CHP2 + Output 2 Chopper enable + 22 + 1 + + + FAULT2 + Output 2 Fault state + 20 + 2 + + + IDLES2 + Output 2 Idle State + 19 + 1 + + + IDLEM2 + Output 2 Idle mode + 18 + 1 + + + POL2 + Output 2 polarity + 17 + 1 + + + DLYPRT + Delayed Protection + 10 + 3 + + + DLYPRTEN + Delayed Protection Enable + 9 + 1 + + + DTEN + Deadtime enable + 8 + 1 + + + DIDL1 + Output 1 Deadtime upon burst mode Idle + entry + 7 + 1 + + + CHP1 + Output 1 Chopper enable + 6 + 1 + + + FAULT1 + Output 1 Fault state + 4 + 2 + + + IDLES1 + Output 1 Idle State + 3 + 1 + + + IDLEM1 + Output 1 Idle mode + 2 + 1 + + + POL1 + Output 1 polarity + 1 + 1 + + + + + FLTER + FLTER + Timerx Fault Register + 0x68 + 0x20 + read-write + 0x00000000 + + + FLTLCK + Fault sources Lock + 31 + 1 + + + FLT5EN + Fault 5 enable + 4 + 1 + + + FLT4EN + Fault 4 enable + 3 + 1 + + + FLT3EN + Fault 3 enable + 2 + 1 + + + FLT2EN + Fault 2 enable + 1 + 1 + + + FLT1EN + Fault 1 enable + 0 + 1 + + + + + + + HRTIM_Common + High Resolution Timer: Common + functions + HRTIM + 0x40017780 + + 0x0 + 0x80 + registers + + + HRTIM_TIME + HRTIM1 timer E interrupt + 108 + + + + CR1 + CR1 + Control Register 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + AD4USRC + ADC Trigger 4 Update + Source + 25 + 3 + + + AD3USRC + ADC Trigger 3 Update + Source + 22 + 3 + + + AD2USRC + ADC Trigger 2 Update + Source + 19 + 3 + + + AD1USRC + ADC Trigger 1 Update + Source + 16 + 3 + + + TEUDIS + Timer E Update Disable + 5 + 1 + + + TDUDIS + Timer D Update Disable + 4 + 1 + + + TCUDIS + Timer C Update Disable + 3 + 1 + + + TBUDIS + Timer B Update Disable + 2 + 1 + + + TAUDIS + Timer A Update Disable + 1 + 1 + + + MUDIS + Master Update Disable + 0 + 1 + + + + + CR2 + CR2 + Control Register 2 + 0x4 + 0x20 + read-write + 0x00000000 + + + TERST + Timer E counter software + reset + 13 + 1 + + + TDRST + Timer D counter software + reset + 12 + 1 + + + TCRST + Timer C counter software + reset + 11 + 1 + + + TBRST + Timer B counter software + reset + 10 + 1 + + + TARST + Timer A counter software + reset + 9 + 1 + + + MRST + Master Counter software + reset + 8 + 1 + + + TESWU + Timer E Software Update + 5 + 1 + + + TDSWU + Timer D Software Update + 4 + 1 + + + TCSWU + Timer C Software Update + 3 + 1 + + + TBSWU + Timer B Software Update + 2 + 1 + + + TASWU + Timer A Software update + 1 + 1 + + + MSWU + Master Timer Software + update + 0 + 1 + + + + + ISR + ISR + Interrupt Status Register + 0x8 + 0x20 + 0x00000000 + + + BMPER + Burst mode Period Interrupt + Flag + 17 + 1 + read-only + + + DLLRDY + DLL Ready Interrupt Flag + 16 + 1 + read-only + + + SYSFLT + System Fault Interrupt + Flag + 5 + 1 + read-write + + + FLT5 + Fault 5 Interrupt Flag + 4 + 1 + read-only + + + FLT4 + Fault 4 Interrupt Flag + 3 + 1 + read-only + + + FLT3 + Fault 3 Interrupt Flag + 2 + 1 + read-only + + + FLT2 + Fault 2 Interrupt Flag + 1 + 1 + read-only + + + FLT1 + Fault 1 Interrupt Flag + 0 + 1 + read-only + + + + + ICR + ICR + Interrupt Clear Register + 0xC + 0x20 + 0x00000000 + + + BMPERC + Burst mode period flag + Clear + 17 + 1 + write-only + + + DLLRDYC + DLL Ready Interrupt flag + Clear + 16 + 1 + write-only + + + SYSFLTC + System Fault Interrupt Flag + Clear + 5 + 1 + read-write + + + FLT5C + Fault 5 Interrupt Flag + Clear + 4 + 1 + write-only + + + FLT4C + Fault 4 Interrupt Flag + Clear + 3 + 1 + write-only + + + FLT3C + Fault 3 Interrupt Flag + Clear + 2 + 1 + write-only + + + FLT2C + Fault 2 Interrupt Flag + Clear + 1 + 1 + write-only + + + FLT1C + Fault 1 Interrupt Flag + Clear + 0 + 1 + write-only + + + + + IER + IER + Interrupt Enable Register + 0x10 + 0x20 + read-write + 0x00000000 + + + BMPERIE + Burst mode period Interrupt + Enable + 17 + 1 + + + DLLRDYIE + DLL Ready Interrupt Enable + 16 + 1 + + + SYSFLTE + System Fault Interrupt + Enable + 5 + 1 + + + FLT5IE + Fault 5 Interrupt Enable + 4 + 1 + + + FLT4IE + Fault 4 Interrupt Enable + 3 + 1 + + + FLT3IE + Fault 3 Interrupt Enable + 2 + 1 + + + FLT2IE + Fault 2 Interrupt Enable + 1 + 1 + + + FLT1IE + Fault 1 Interrupt Enable + 0 + 1 + + + + + OENR + OENR + Output Enable Register + 0x14 + 0x20 + write-only + 0x00000000 + + + TE2OEN + Timer E Output 2 Enable + 9 + 1 + + + TE1OEN + Timer E Output 1 Enable + 8 + 1 + + + TD2OEN + Timer D Output 2 Enable + 7 + 1 + + + TD1OEN + Timer D Output 1 Enable + 6 + 1 + + + TC2OEN + Timer C Output 2 Enable + 5 + 1 + + + TC1OEN + Timer C Output 1 Enable + 4 + 1 + + + TB2OEN + Timer B Output 2 Enable + 3 + 1 + + + TB1OEN + Timer B Output 1 Enable + 2 + 1 + + + TA2OEN + Timer A Output 2 Enable + 1 + 1 + + + TA1OEN + Timer A Output 1 Enable + 0 + 1 + + + + + DISR + DISR + DISR + 0x18 + 0x20 + read-write + 0x00000000 + + + TE2ODIS + TE2ODIS + 9 + 1 + + + TE1ODIS + TE1ODIS + 8 + 1 + + + TD2ODIS + TD2ODIS + 7 + 1 + + + TD1ODIS + TD1ODIS + 6 + 1 + + + TC2ODIS + TC2ODIS + 5 + 1 + + + TC1ODIS + TC1ODIS + 4 + 1 + + + TB2ODIS + TB2ODIS + 3 + 1 + + + TB1ODIS + TB1ODIS + 2 + 1 + + + TA2ODIS + TA2ODIS + 1 + 1 + + + TA1ODIS + TA1ODIS + 0 + 1 + + + + + ODSR + ODSR + Output Disable Status Register + 0x1C + 0x20 + read-only + 0x00000000 + + + TE2ODS + Timer E Output 2 disable + status + 9 + 1 + + + TE1ODS + Timer E Output 1 disable + status + 8 + 1 + + + TD2ODS + Timer D Output 2 disable + status + 7 + 1 + + + TD1ODS + Timer D Output 1 disable + status + 6 + 1 + + + TC2ODS + Timer C Output 2 disable + status + 5 + 1 + + + TC1ODS + Timer C Output 1 disable + status + 4 + 1 + + + TB2ODS + Timer B Output 2 disable + status + 3 + 1 + + + TB1ODS + Timer B Output 1 disable + status + 2 + 1 + + + TA2ODS + Timer A Output 2 disable + status + 1 + 1 + + + TA1ODS + Timer A Output 1 disable + status + 0 + 1 + + + + + BMCR + BMCR + Burst Mode Control Register + 0x20 + 0x20 + read-write + 0x00000000 + + + BMSTAT + Burst Mode Status + 31 + 1 + + + TEBM + Timer E Burst Mode + 21 + 1 + + + TDBM + Timer D Burst Mode + 20 + 1 + + + TCBM + Timer C Burst Mode + 19 + 1 + + + TBBM + Timer B Burst Mode + 18 + 1 + + + TABM + Timer A Burst Mode + 17 + 1 + + + MTBM + Master Timer Burst Mode + 16 + 1 + + + BMPREN + Burst Mode Preload Enable + 10 + 1 + + + BMPRSC + Burst Mode Prescaler + 6 + 4 + + + BMCLK + Burst Mode Clock source + 2 + 4 + + + BMOM + Burst Mode operating mode + 1 + 1 + + + BME + Burst Mode enable + 0 + 1 + + + + + BMTRG + BMTRG + BMTRG + 0x24 + 0x20 + read-write + 0x00000000 + + + OCHPEV + OCHPEV + 31 + 1 + + + TECMP2 + TECMP2 + 26 + 1 + + + TECMP1 + TECMP1 + 25 + 1 + + + TEREP + TEREP + 24 + 1 + + + TERST + TERST + 23 + 1 + + + TDCMP2 + TDCMP2 + 22 + 1 + + + TDCMP1 + TDCMP1 + 21 + 1 + + + TDREP + TDREP + 20 + 1 + + + TDRST + TDRST + 19 + 1 + + + TCCMP2 + TCCMP2 + 18 + 1 + + + TCCMP1 + TCCMP1 + 17 + 1 + + + TCREP + TCREP + 16 + 1 + + + TCRST + TCRST + 15 + 1 + + + TBCMP2 + TBCMP2 + 14 + 1 + + + TBCMP1 + TBCMP1 + 13 + 1 + + + TBREP + TBREP + 12 + 1 + + + TBRST + TBRST + 11 + 1 + + + TACMP2 + TACMP2 + 10 + 1 + + + TACMP1 + TACMP1 + 9 + 1 + + + TAREP + TAREP + 8 + 1 + + + TARST + TARST + 7 + 1 + + + MSTCMP4 + MSTCMP4 + 6 + 1 + + + MSTCMP3 + MSTCMP3 + 5 + 1 + + + MSTCMP2 + MSTCMP2 + 4 + 1 + + + MSTCMP1 + MSTCMP1 + 3 + 1 + + + MSTREP + MSTREP + 2 + 1 + + + MSTRST + MSTRST + 1 + 1 + + + SW + SW + 0 + 1 + + + + + BMCMPR6 + BMCMPR6 + BMCMPR6 + 0x28 + 0x20 + read-write + 0x00000000 + + + BMCMP + BMCMP + 0 + 16 + + + + + BMPER + BMPER + Burst Mode Period Register + 0x2C + 0x20 + read-write + 0x00000000 + + + BMPER + Burst mode Period + 0 + 16 + + + + + EECR1 + EECR1 + Timer External Event Control Register + 1 + 0x30 + 0x20 + read-write + 0x00000000 + + + EE5FAST + External Event 5 Fast mode + 29 + 1 + + + EE5SNS + External Event 5 + Sensitivity + 27 + 2 + + + EE5POL + External Event 5 Polarity + 26 + 1 + + + EE5SRC + External Event 5 Source + 24 + 2 + + + EE4FAST + External Event 4 Fast mode + 23 + 1 + + + EE4SNS + External Event 4 + Sensitivity + 21 + 2 + + + EE4POL + External Event 4 Polarity + 20 + 1 + + + EE4SRC + External Event 4 Source + 18 + 2 + + + EE3FAST + External Event 3 Fast mode + 17 + 1 + + + EE3SNS + External Event 3 + Sensitivity + 15 + 2 + + + EE3POL + External Event 3 Polarity + 14 + 1 + + + EE3SRC + External Event 3 Source + 12 + 2 + + + EE2FAST + External Event 2 Fast mode + 11 + 1 + + + EE2SNS + External Event 2 + Sensitivity + 9 + 2 + + + EE2POL + External Event 2 Polarity + 8 + 1 + + + EE2SRC + External Event 2 Source + 6 + 2 + + + EE1FAST + External Event 1 Fast mode + 5 + 1 + + + EE1SNS + External Event 1 + Sensitivity + 3 + 2 + + + EE1POL + External Event 1 Polarity + 2 + 1 + + + EE1SRC + External Event 1 Source + 0 + 2 + + + + + EECR2 + EECR2 + Timer External Event Control Register + 2 + 0x34 + 0x20 + read-write + 0x00000000 + + + EE10SNS + External Event 10 + Sensitivity + 27 + 2 + + + EE10POL + External Event 10 Polarity + 26 + 1 + + + EE10SRC + External Event 10 Source + 24 + 2 + + + EE9SNS + External Event 9 + Sensitivity + 21 + 2 + + + EE9POL + External Event 9 Polarity + 20 + 1 + + + EE9SRC + External Event 9 Source + 18 + 2 + + + EE8SNS + External Event 8 + Sensitivity + 15 + 2 + + + EE8POL + External Event 8 Polarity + 14 + 1 + + + EE8SRC + External Event 8 Source + 12 + 2 + + + EE7SNS + External Event 7 + Sensitivity + 9 + 2 + + + EE7POL + External Event 7 Polarity + 8 + 1 + + + EE7SRC + External Event 7 Source + 6 + 2 + + + EE6SNS + External Event 6 + Sensitivity + 3 + 2 + + + EE6POL + External Event 6 Polarity + 2 + 1 + + + EE6SRC + External Event 6 Source + 0 + 2 + + + + + EECR3 + EECR3 + Timer External Event Control Register + 3 + 0x38 + 0x20 + read-write + 0x00000000 + + + EE10SNS + EE10SNS + 27 + 2 + + + EE10POL + EE10POL + 26 + 1 + + + EE10SRC + EE10SRC + 24 + 2 + + + EE9SNS + EE9SNS + 21 + 2 + + + EE9POL + EE9POL + 20 + 1 + + + EE9SRC + EE9SRC + 18 + 2 + + + EE8SNS + EE8SNS + 15 + 2 + + + EE8POL + EE8POL + 14 + 1 + + + EE8SRC + EE8SRC + 12 + 2 + + + EE7SNS + EE7SNS + 9 + 2 + + + EE7POL + EE7POL + 8 + 1 + + + EE7SRC + EE7SRC + 6 + 2 + + + EE6SNS + EE6SNS + 3 + 2 + + + EE6POL + EE6POL + 2 + 1 + + + EE6SRC + EE6SRC + 0 + 2 + + + + + ADC1R + ADC1R + ADC Trigger 1 Register + 0x3C + 0x20 + read-write + 0x00000000 + + + AD1TEPER + ADC trigger 1 on Timer E + Period + 31 + 1 + + + AD1TEC4 + ADC trigger 1 on Timer E compare + 4 + 30 + 1 + + + AD1TEC3 + ADC trigger 1 on Timer E compare + 3 + 29 + 1 + + + AD1TEC2 + ADC trigger 1 on Timer E compare + 2 + 28 + 1 + + + AD1TDPER + ADC trigger 1 on Timer D + Period + 27 + 1 + + + AD1TDC4 + ADC trigger 1 on Timer D compare + 4 + 26 + 1 + + + AD1TDC3 + ADC trigger 1 on Timer D compare + 3 + 25 + 1 + + + AD1TDC2 + ADC trigger 1 on Timer D compare + 2 + 24 + 1 + + + AD1TCPER + ADC trigger 1 on Timer C + Period + 23 + 1 + + + AD1TCC4 + ADC trigger 1 on Timer C compare + 4 + 22 + 1 + + + AD1TCC3 + ADC trigger 1 on Timer C compare + 3 + 21 + 1 + + + AD1TCC2 + ADC trigger 1 on Timer C compare + 2 + 20 + 1 + + + AD1TBRST + ADC trigger 1 on Timer B + Reset + 19 + 1 + + + AD1TBPER + ADC trigger 1 on Timer B + Period + 18 + 1 + + + AD1TBC4 + ADC trigger 1 on Timer B compare + 4 + 17 + 1 + + + AD1TBC3 + ADC trigger 1 on Timer B compare + 3 + 16 + 1 + + + AD1TBC2 + ADC trigger 1 on Timer B compare + 2 + 15 + 1 + + + AD1TARST + ADC trigger 1 on Timer A + Reset + 14 + 1 + + + AD1TAPER + ADC trigger 1 on Timer A + Period + 13 + 1 + + + AD1TAC4 + ADC trigger 1 on Timer A compare + 4 + 12 + 1 + + + AD1TAC3 + ADC trigger 1 on Timer A compare + 3 + 11 + 1 + + + AD1TAC2 + ADC trigger 1 on Timer A compare + 2 + 10 + 1 + + + AD1EEV5 + ADC trigger 1 on External Event + 5 + 9 + 1 + + + AD1EEV4 + ADC trigger 1 on External Event + 4 + 8 + 1 + + + AD1EEV3 + ADC trigger 1 on External Event + 3 + 7 + 1 + + + AD1EEV2 + ADC trigger 1 on External Event + 2 + 6 + 1 + + + AD1EEV1 + ADC trigger 1 on External Event + 1 + 5 + 1 + + + AD1MPER + ADC trigger 1 on Master + Period + 4 + 1 + + + AD1MC4 + ADC trigger 1 on Master Compare + 4 + 3 + 1 + + + AD1MC3 + ADC trigger 1 on Master Compare + 3 + 2 + 1 + + + AD1MC2 + ADC trigger 1 on Master Compare + 2 + 1 + 1 + + + AD1MC1 + ADC trigger 1 on Master Compare + 1 + 0 + 1 + + + + + ADC2R + ADC2R + ADC Trigger 2 Register + 0x40 + 0x20 + read-write + 0x00000000 + + + AD2TERST + ADC trigger 2 on Timer E + Reset + 31 + 1 + + + AD2TEC4 + ADC trigger 2 on Timer E compare + 4 + 30 + 1 + + + AD2TEC3 + ADC trigger 2 on Timer E compare + 3 + 29 + 1 + + + AD2TEC2 + ADC trigger 2 on Timer E compare + 2 + 28 + 1 + + + AD2TDRST + ADC trigger 2 on Timer D + Reset + 27 + 1 + + + AD2TDPER + ADC trigger 2 on Timer D + Period + 26 + 1 + + + AD2TDC4 + ADC trigger 2 on Timer D compare + 4 + 25 + 1 + + + AD2TDC3 + ADC trigger 2 on Timer D compare + 3 + 24 + 1 + + + AD2TDC2 + ADC trigger 2 on Timer D compare + 2 + 23 + 1 + + + AD2TCRST + ADC trigger 2 on Timer C + Reset + 22 + 1 + + + AD2TCPER + ADC trigger 2 on Timer C + Period + 21 + 1 + + + AD2TCC4 + ADC trigger 2 on Timer C compare + 4 + 20 + 1 + + + AD2TCC3 + ADC trigger 2 on Timer C compare + 3 + 19 + 1 + + + AD2TCC2 + ADC trigger 2 on Timer C compare + 2 + 18 + 1 + + + AD2TBPER + ADC trigger 2 on Timer B + Period + 17 + 1 + + + AD2TBC4 + ADC trigger 2 on Timer B compare + 4 + 16 + 1 + + + AD2TBC3 + ADC trigger 2 on Timer B compare + 3 + 15 + 1 + + + AD2TBC2 + ADC trigger 2 on Timer B compare + 2 + 14 + 1 + + + AD2TAPER + ADC trigger 2 on Timer A + Period + 13 + 1 + + + AD2TAC4 + ADC trigger 2 on Timer A compare + 4 + 12 + 1 + + + AD2TAC3 + ADC trigger 2 on Timer A compare + 3 + 11 + 1 + + + AD2TAC2 + ADC trigger 2 on Timer A compare + 2 + 10 + 1 + + + AD2EEV10 + ADC trigger 2 on External Event + 10 + 9 + 1 + + + AD2EEV9 + ADC trigger 2 on External Event + 9 + 8 + 1 + + + AD2EEV8 + ADC trigger 2 on External Event + 8 + 7 + 1 + + + AD2EEV7 + ADC trigger 2 on External Event + 7 + 6 + 1 + + + AD2EEV6 + ADC trigger 2 on External Event + 6 + 5 + 1 + + + AD2MPER + ADC trigger 2 on Master + Period + 4 + 1 + + + AD2MC4 + ADC trigger 2 on Master Compare + 4 + 3 + 1 + + + AD2MC3 + ADC trigger 2 on Master Compare + 3 + 2 + 1 + + + AD2MC2 + ADC trigger 2 on Master Compare + 2 + 1 + 1 + + + AD2MC1 + ADC trigger 2 on Master Compare + 1 + 0 + 1 + + + + + ADC3R + ADC3R + ADC Trigger 3 Register + 0x44 + 0x20 + read-write + 0x00000000 + + + AD1TEPER + AD1TEPER + 31 + 1 + + + AD1TEC4 + AD1TEC4 + 30 + 1 + + + AD1TEC3 + AD1TEC3 + 29 + 1 + + + AD1TEC2 + AD1TEC2 + 28 + 1 + + + AD1TDPER + AD1TDPER + 27 + 1 + + + AD1TDC4 + AD1TDC4 + 26 + 1 + + + AD1TDC3 + AD1TDC3 + 25 + 1 + + + AD1TDC2 + AD1TDC2 + 24 + 1 + + + AD1TCPER + AD1TCPER + 23 + 1 + + + AD1TCC4 + AD1TCC4 + 22 + 1 + + + AD1TCC3 + AD1TCC3 + 21 + 1 + + + AD1TCC2 + AD1TCC2 + 20 + 1 + + + AD1TBRST + AD1TBRST + 19 + 1 + + + AD1TBPER + AD1TBPER + 18 + 1 + + + AD1TBC4 + AD1TBC4 + 17 + 1 + + + AD1TBC3 + AD1TBC3 + 16 + 1 + + + AD1TBC2 + AD1TBC2 + 15 + 1 + + + AD1TARST + AD1TARST + 14 + 1 + + + AD1TAPER + AD1TAPER + 13 + 1 + + + AD1TAC4 + AD1TAC4 + 12 + 1 + + + AD1TAC3 + AD1TAC3 + 11 + 1 + + + AD1TAC2 + AD1TAC2 + 10 + 1 + + + AD1EEV5 + AD1EEV5 + 9 + 1 + + + AD1EEV4 + AD1EEV4 + 8 + 1 + + + AD1EEV3 + AD1EEV3 + 7 + 1 + + + AD1EEV2 + AD1EEV2 + 6 + 1 + + + AD1EEV1 + AD1EEV1 + 5 + 1 + + + AD1MPER + AD1MPER + 4 + 1 + + + AD1MC4 + AD1MC4 + 3 + 1 + + + AD1MC3 + AD1MC3 + 2 + 1 + + + AD1MC2 + AD1MC2 + 1 + 1 + + + AD1MC1 + AD1MC1 + 0 + 1 + + + + + ADC4R + ADC4R + ADC Trigger 4 Register + 0x48 + 0x20 + read-write + 0x00000000 + + + AD2TERST + AD2TERST + 31 + 1 + + + AD2TEC4 + AD2TEC4 + 30 + 1 + + + AD2TEC3 + AD2TEC3 + 29 + 1 + + + AD2TEC2 + AD2TEC2 + 28 + 1 + + + AD2TDRST + AD2TDRST + 27 + 1 + + + AD2TDPER + AD2TDPER + 26 + 1 + + + AD2TDC4 + AD2TDC4 + 25 + 1 + + + AD2TDC3 + AD2TDC3 + 24 + 1 + + + AD2TDC2 + AD2TDC2 + 23 + 1 + + + AD2TCRST + AD2TCRST + 22 + 1 + + + AD2TCPER + AD2TCPER + 21 + 1 + + + AD2TCC4 + AD2TCC4 + 20 + 1 + + + AD2TCC3 + AD2TCC3 + 19 + 1 + + + AD2TCC2 + AD2TCC2 + 18 + 1 + + + AD2TBPER + AD2TBPER + 17 + 1 + + + AD2TBC4 + AD2TBC4 + 16 + 1 + + + AD2TBC3 + AD2TBC3 + 15 + 1 + + + AD2TBC2 + AD2TBC2 + 14 + 1 + + + AD2TAPER + AD2TAPER + 13 + 1 + + + AD2TAC4 + AD2TAC4 + 12 + 1 + + + AD2TAC3 + AD2TAC3 + 11 + 1 + + + AD2TAC2 + AD2TAC2 + 10 + 1 + + + AD2EEV10 + AD2EEV10 + 9 + 1 + + + AD2EEV9 + AD2EEV9 + 8 + 1 + + + AD2EEV8 + AD2EEV8 + 7 + 1 + + + AD2EEV7 + AD2EEV7 + 6 + 1 + + + AD2EEV6 + AD2EEV6 + 5 + 1 + + + AD2MPER + AD2MPER + 4 + 1 + + + AD2MC4 + AD2MC4 + 3 + 1 + + + AD2MC3 + AD2MC3 + 2 + 1 + + + AD2MC2 + AD2MC2 + 1 + 1 + + + AD2MC1 + AD2MC1 + 0 + 1 + + + + + DLLCR + DLLCR + DLL Control Register + 0x4C + 0x20 + read-write + 0x00000000 + + + CALRTE + DLL Calibration rate + 2 + 2 + + + CALEN + DLL Calibration Enable + 1 + 1 + + + CAL + DLL Calibration Start + 0 + 1 + + + + + FLTINR1 + FLTINR1 + HRTIM Fault Input Register 1 + 0x50 + 0x20 + read-write + 0x00000000 + + + FLT4LCK + FLT4LCK + 31 + 1 + + + FLT4F + FLT4F + 27 + 4 + + + FLT4SRC + FLT4SRC + 26 + 1 + + + FLT4P + FLT4P + 25 + 1 + + + FLT4E + FLT4E + 24 + 1 + + + FLT3LCK + FLT3LCK + 23 + 1 + + + FLT3F + FLT3F + 19 + 4 + + + FLT3SRC + FLT3SRC + 18 + 1 + + + FLT3P + FLT3P + 17 + 1 + + + FLT3E + FLT3E + 16 + 1 + + + FLT2LCK + FLT2LCK + 15 + 1 + + + FLT2F + FLT2F + 11 + 4 + + + FLT2SRC + FLT2SRC + 10 + 1 + + + FLT2P + FLT2P + 9 + 1 + + + FLT2E + FLT2E + 8 + 1 + + + FLT1LCK + FLT1LCK + 7 + 1 + + + FLT1F + FLT1F + 3 + 4 + + + FLT1SRC + FLT1SRC + 2 + 1 + + + FLT1P + FLT1P + 1 + 1 + + + FLT1E + FLT1E + 0 + 1 + + + + + FLTINR2 + FLTINR2 + HRTIM Fault Input Register 2 + 0x54 + 0x20 + read-write + 0x00000000 + + + FLTSD + FLTSD + 24 + 2 + + + FLT5LCK + FLT5LCK + 7 + 1 + + + FLT5F + FLT5F + 3 + 4 + + + FLT5SRC + FLT5SRC + 2 + 1 + + + FLT5P + FLT5P + 1 + 1 + + + FLT5E + FLT5E + 0 + 1 + + + + + BDMUPDR + BDMUPDR + BDMUPDR + 0x58 + 0x20 + read-write + 0x00000000 + + + MCMP4 + MCMP4 + 9 + 1 + + + MCMP3 + MCMP3 + 8 + 1 + + + MCMP2 + MCMP2 + 7 + 1 + + + MCMP1 + MCMP1 + 6 + 1 + + + MREP + MREP + 5 + 1 + + + MPER + MPER + 4 + 1 + + + MCNT + MCNT + 3 + 1 + + + MDIER + MDIER + 2 + 1 + + + MICR + MICR + 1 + 1 + + + MCR + MCR + 0 + 1 + + + + + BDTxUPR + BDTxUPR + Burst DMA Timerx update + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + TIMxFLTR + HRTIM_FLTxR register update + enable + 20 + 1 + + + TIMxOUTR + HRTIM_OUTxR register update + enable + 19 + 1 + + + TIMxCHPR + HRTIM_CHPxR register update + enable + 18 + 1 + + + TIMxRSTR + HRTIM_RSTxR register update + enable + 17 + 1 + + + TIMxEEFR2 + HRTIM_EEFxR2 register update + enable + 16 + 1 + + + TIMxEEFR1 + HRTIM_EEFxR1 register update + enable + 15 + 1 + + + TIMxRST2R + HRTIM_RST2xR register update + enable + 14 + 1 + + + TIMxSET2R + HRTIM_SET2xR register update + enable + 13 + 1 + + + TIMxRST1R + HRTIM_RST1xR register update + enable + 12 + 1 + + + TIMxSET1R + HRTIM_SET1xR register update + enable + 11 + 1 + + + TIMx_DTxR + HRTIM_DTxR register update + enable + 10 + 1 + + + TIMxCMP4 + HRTIM_CMP4xR register update + enable + 9 + 1 + + + TIMxCMP3 + HRTIM_CMP3xR register update + enable + 8 + 1 + + + TIMxCMP2 + HRTIM_CMP2xR register update + enable + 7 + 1 + + + TIMxCMP1 + HRTIM_CMP1xR register update + enable + 6 + 1 + + + TIMxREP + HRTIM_REPxR register update + enable + 5 + 1 + + + TIMxPER + HRTIM_PERxR register update + enable + 4 + 1 + + + TIMxCNT + HRTIM_CNTxR register update + enable + 3 + 1 + + + TIMxDIER + HRTIM_TIMxDIER register update + enable + 2 + 1 + + + TIMxICR + HRTIM_TIMxICR register update + enable + 1 + 1 + + + TIMxCR + HRTIM_TIMxCR register update + enable + 0 + 1 + + + + + BDMADR + BDMADR + Burst DMA Data Register + 0x60 + 0x20 + read-write + 0x00000000 + + + BDMADR + Burst DMA Data register + 0 + 32 + + + + + + + DFSDM + Digital filter for sigma delta + modulators + DFSDM + 0x40017000 + + 0x0 + 0x400 + registers + + + DFSDM1_FLT0 + DFSDM1 filter 0 interrupt + 110 + + + DFSDM1_FLT1 + DFSDM1 filter 1 interrupt + 111 + + + DFSDM1_FLT2 + DFSDM1 filter 2 interrupt + 112 + + + DFSDM1_FLT3 + DFSDM1 filter 3 interrupt + 113 + + + + DFSDM_CHCFG0R1 + DFSDM_CHCFG0R1 + DFSDM channel configuration 0 register + 1 + 0x0 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 0 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 0 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 0 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 0 + 6 + 1 + + + CHEN + Channel 0 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 0 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG1R1 + DFSDM_CHCFG1R1 + DFSDM channel configuration 1 register + 1 + 0x4 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 1 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 1 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 1 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 1 + 6 + 1 + + + CHEN + Channel 1 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 1 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG2R1 + DFSDM_CHCFG2R1 + DFSDM channel configuration 2 register + 1 + 0x8 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 2 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 2 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 2 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 2 + 6 + 1 + + + CHEN + Channel 2 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 2 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG3R1 + DFSDM_CHCFG3R1 + DFSDM channel configuration 3 register + 1 + 0xC + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 3 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 3 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 3 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 3 + 6 + 1 + + + CHEN + Channel 3 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 3 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG4R1 + DFSDM_CHCFG4R1 + DFSDM channel configuration 4 register + 1 + 0x10 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 4 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 4 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 4 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 4 + 6 + 1 + + + CHEN + Channel 4 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 4 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG5R1 + DFSDM_CHCFG5R1 + DFSDM channel configuration 5 register + 1 + 0x14 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 5 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 5 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 5 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 5 + 6 + 1 + + + CHEN + Channel 5 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 5 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG6R1 + DFSDM_CHCFG6R1 + DFSDM channel configuration 6 register + 1 + 0x18 + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 6 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 6 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 6 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 6 + 6 + 1 + + + CHEN + Channel 6 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 6 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG7R1 + DFSDM_CHCFG7R1 + DFSDM channel configuration 7 register + 1 + 0x1C + 0x20 + read-write + 0x00000000 + + + SITP + Serial interface type for channel + 7 + 0 + 2 + + + SPICKSEL + SPI clock select for channel + 7 + 2 + 2 + + + SCDEN + Short-circuit detector enable on channel + 7 + 5 + 1 + + + CKABEN + Clock absence detector enable on channel + 7 + 6 + 1 + + + CHEN + Channel 7 enable + 7 + 1 + + + CHINSEL + Channel inputs selection + 8 + 1 + + + DATMPX + Input data multiplexer for channel + 7 + 12 + 2 + + + DATPACK + Data packing mode in DFSDM_CHDATINyR + register + 14 + 2 + + + CKOUTDIV + Output serial clock + divider + 16 + 8 + + + CKOUTSRC + Output serial clock source + selection + 30 + 1 + + + DFSDMEN + Global enable for DFSDM + interface + 31 + 1 + + + + + DFSDM_CHCFG0R2 + DFSDM_CHCFG0R2 + DFSDM channel configuration 0 register + 2 + 0x20 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 0 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 0 + 8 + 24 + + + + + DFSDM_CHCFG1R2 + DFSDM_CHCFG1R2 + DFSDM channel configuration 1 register + 2 + 0x24 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 1 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 1 + 8 + 24 + + + + + DFSDM_CHCFG2R2 + DFSDM_CHCFG2R2 + DFSDM channel configuration 2 register + 2 + 0x28 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 2 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 2 + 8 + 24 + + + + + DFSDM_CHCFG3R2 + DFSDM_CHCFG3R2 + DFSDM channel configuration 3 register + 2 + 0x2C + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 3 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 3 + 8 + 24 + + + + + DFSDM_CHCFG4R2 + DFSDM_CHCFG4R2 + DFSDM channel configuration 4 register + 2 + 0x30 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 4 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 4 + 8 + 24 + + + + + DFSDM_CHCFG5R2 + DFSDM_CHCFG5R2 + DFSDM channel configuration 5 register + 2 + 0x34 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 5 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 5 + 8 + 24 + + + + + DFSDM_CHCFG6R2 + DFSDM_CHCFG6R2 + DFSDM channel configuration 6 register + 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 6 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 6 + 8 + 24 + + + + + DFSDM_CHCFG7R2 + DFSDM_CHCFG7R2 + DFSDM channel configuration 7 register + 2 + 0x3C + 0x20 + read-write + 0x00000000 + + + DTRBS + Data right bit-shift for channel + 7 + 3 + 5 + + + OFFSET + 24-bit calibration offset for channel + 7 + 8 + 24 + + + + + DFSDM_AWSCD0R + DFSDM_AWSCD0R + DFSDM analog watchdog and short-circuit + detector register + 0x40 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 0 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 0 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 0 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 0 + 22 + 2 + + + + + DFSDM_AWSCD1R + DFSDM_AWSCD1R + DFSDM analog watchdog and short-circuit + detector register + 0x44 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 1 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 1 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 1 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 1 + 22 + 2 + + + + + DFSDM_AWSCD2R + DFSDM_AWSCD2R + DFSDM analog watchdog and short-circuit + detector register + 0x48 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 2 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 2 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 2 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 2 + 22 + 2 + + + + + DFSDM_AWSCD3R + DFSDM_AWSCD3R + DFSDM analog watchdog and short-circuit + detector register + 0x4C + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 3 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 3 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 3 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 3 + 22 + 2 + + + + + DFSDM_AWSCD4R + DFSDM_AWSCD4R + DFSDM analog watchdog and short-circuit + detector register + 0x50 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 4 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 4 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 4 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 4 + 22 + 2 + + + + + DFSDM_AWSCD5R + DFSDM_AWSCD5R + DFSDM analog watchdog and short-circuit + detector register + 0x54 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 5 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 5 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 5 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 5 + 22 + 2 + + + + + DFSDM_AWSCD6R + DFSDM_AWSCD6R + DFSDM analog watchdog and short-circuit + detector register + 0x58 + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 6 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 6 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 6 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 6 + 22 + 2 + + + + + DFSDM_AWSCD7R + DFSDM_AWSCD7R + DFSDM analog watchdog and short-circuit + detector register + 0x5C + 0x20 + read-write + 0x00000000 + + + SCDT + short-circuit detector threshold for + channel 7 + 0 + 8 + + + BKSCD + Break signal assignment for + short-circuit detector on channel 7 + 12 + 4 + + + AWFOSR + Analog watchdog filter oversampling + ratio (decimation rate) on channel 7 + 16 + 5 + + + AWFORD + Analog watchdog Sinc filter order on + channel 7 + 22 + 2 + + + + + DFSDM_CHWDAT0R + DFSDM_CHWDAT0R + DFSDM channel watchdog filter data + register + 0x60 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT1R + DFSDM_CHWDAT1R + DFSDM channel watchdog filter data + register + 0x64 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT2R + DFSDM_CHWDAT2R + DFSDM channel watchdog filter data + register + 0x68 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT3R + DFSDM_CHWDAT3R + DFSDM channel watchdog filter data + register + 0x6C + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT4R + DFSDM_CHWDAT4R + DFSDM channel watchdog filter data + register + 0x70 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT5R + DFSDM_CHWDAT5R + DFSDM channel watchdog filter data + register + 0x74 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT6R + DFSDM_CHWDAT6R + DFSDM channel watchdog filter data + register + 0x78 + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHWDAT7R + DFSDM_CHWDAT7R + DFSDM channel watchdog filter data + register + 0x7C + 0x20 + read-only + 0x00000000 + + + WDATA + Input channel y watchdog + data + 0 + 16 + + + + + DFSDM_CHDATIN0R + DFSDM_CHDATIN0R + DFSDM channel data input + register + 0x80 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 0 + 0 + 16 + + + INDAT1 + Input data for channel 1 + 16 + 16 + + + + + DFSDM_CHDATIN1R + DFSDM_CHDATIN1R + DFSDM channel data input + register + 0x84 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 1 + 0 + 16 + + + INDAT1 + Input data for channel 2 + 16 + 16 + + + + + DFSDM_CHDATIN2R + DFSDM_CHDATIN2R + DFSDM channel data input + register + 0x88 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 2 + 0 + 16 + + + INDAT1 + Input data for channel 3 + 16 + 16 + + + + + DFSDM_CHDATIN3R + DFSDM_CHDATIN3R + DFSDM channel data input + register + 0x8C + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 3 + 0 + 16 + + + INDAT1 + Input data for channel 4 + 16 + 16 + + + + + DFSDM_CHDATIN4R + DFSDM_CHDATIN4R + DFSDM channel data input + register + 0x90 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 4 + 0 + 16 + + + INDAT1 + Input data for channel 5 + 16 + 16 + + + + + DFSDM_CHDATIN5R + DFSDM_CHDATIN5R + DFSDM channel data input + register + 0x94 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 5 + 0 + 16 + + + INDAT1 + Input data for channel 6 + 16 + 16 + + + + + DFSDM_CHDATIN6R + DFSDM_CHDATIN6R + DFSDM channel data input + register + 0x98 + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 6 + 0 + 16 + + + INDAT1 + Input data for channel 7 + 16 + 16 + + + + + DFSDM_CHDATIN7R + DFSDM_CHDATIN7R + DFSDM channel data input + register + 0x9C + 0x20 + read-write + 0x00000000 + + + INDAT0 + Input data for channel 7 + 0 + 16 + + + INDAT1 + Input data for channel 8 + 16 + 16 + + + + + DFSDM0_CR1 + DFSDM0_CR1 + DFSDM control register 1 + 0xA0 + 0x20 + read-write + 0x00000000 + + + DFEN + DFSDM enable + 0 + 1 + + + JSWSTART + Start a conversion of the injected group + of channels + 1 + 1 + + + JSYNC + Launch an injected conversion + synchronously with the DFSDM0 JSWSTART + trigger + 3 + 1 + + + JSCAN + Scanning conversion mode for injected + conversions + 4 + 1 + + + JDMAEN + DMA channel enabled to read data for the + injected channel group + 5 + 1 + + + JEXTSEL + Trigger signal selection for launching + injected conversions + 8 + 5 + + + JEXTEN + Trigger enable and trigger edge + selection for injected conversions + 13 + 2 + + + RSWSTART + Software start of a conversion on the + regular channel + 17 + 1 + + + RCONT + Continuous mode selection for regular + conversions + 18 + 1 + + + RSYNC + Launch regular conversion synchronously + with DFSDM0 + 19 + 1 + + + RDMAEN + DMA channel enabled to read data for the + regular conversion + 21 + 1 + + + RCH + Regular channel selection + 24 + 3 + + + FAST + Fast conversion mode selection for + regular conversions + 29 + 1 + + + AWFSEL + Analog watchdog fast mode + select + 30 + 1 + + + + + DFSDM1_CR1 + DFSDM1_CR1 + DFSDM control register 1 + 0xA4 + 0x20 + read-write + 0x00000000 + + + DFEN + DFSDM enable + 0 + 1 + + + JSWSTART + Start a conversion of the injected group + of channels + 1 + 1 + + + JSYNC + Launch an injected conversion + synchronously with the DFSDM0 JSWSTART + trigger + 3 + 1 + + + JSCAN + Scanning conversion mode for injected + conversions + 4 + 1 + + + JDMAEN + DMA channel enabled to read data for the + injected channel group + 5 + 1 + + + JEXTSEL + Trigger signal selection for launching + injected conversions + 8 + 5 + + + JEXTEN + Trigger enable and trigger edge + selection for injected conversions + 13 + 2 + + + RSWSTART + Software start of a conversion on the + regular channel + 17 + 1 + + + RCONT + Continuous mode selection for regular + conversions + 18 + 1 + + + RSYNC + Launch regular conversion synchronously + with DFSDM0 + 19 + 1 + + + RDMAEN + DMA channel enabled to read data for the + regular conversion + 21 + 1 + + + RCH + Regular channel selection + 24 + 3 + + + FAST + Fast conversion mode selection for + regular conversions + 29 + 1 + + + AWFSEL + Analog watchdog fast mode + select + 30 + 1 + + + + + DFSDM2_CR1 + DFSDM2_CR1 + DFSDM control register 1 + 0xA8 + 0x20 + read-write + 0x00000000 + + + DFEN + DFSDM enable + 0 + 1 + + + JSWSTART + Start a conversion of the injected group + of channels + 1 + 1 + + + JSYNC + Launch an injected conversion + synchronously with the DFSDM0 JSWSTART + trigger + 3 + 1 + + + JSCAN + Scanning conversion mode for injected + conversions + 4 + 1 + + + JDMAEN + DMA channel enabled to read data for the + injected channel group + 5 + 1 + + + JEXTSEL + Trigger signal selection for launching + injected conversions + 8 + 5 + + + JEXTEN + Trigger enable and trigger edge + selection for injected conversions + 13 + 2 + + + RSWSTART + Software start of a conversion on the + regular channel + 17 + 1 + + + RCONT + Continuous mode selection for regular + conversions + 18 + 1 + + + RSYNC + Launch regular conversion synchronously + with DFSDM0 + 19 + 1 + + + RDMAEN + DMA channel enabled to read data for the + regular conversion + 21 + 1 + + + RCH + Regular channel selection + 24 + 3 + + + FAST + Fast conversion mode selection for + regular conversions + 29 + 1 + + + AWFSEL + Analog watchdog fast mode + select + 30 + 1 + + + + + DFSDM3_CR1 + DFSDM3_CR1 + DFSDM control register 1 + 0xAC + 0x20 + read-write + 0x00000000 + + + DFEN + DFSDM enable + 0 + 1 + + + JSWSTART + Start a conversion of the injected group + of channels + 1 + 1 + + + JSYNC + Launch an injected conversion + synchronously with the DFSDM0 JSWSTART + trigger + 3 + 1 + + + JSCAN + Scanning conversion mode for injected + conversions + 4 + 1 + + + JDMAEN + DMA channel enabled to read data for the + injected channel group + 5 + 1 + + + JEXTSEL + Trigger signal selection for launching + injected conversions + 8 + 5 + + + JEXTEN + Trigger enable and trigger edge + selection for injected conversions + 13 + 2 + + + RSWSTART + Software start of a conversion on the + regular channel + 17 + 1 + + + RCONT + Continuous mode selection for regular + conversions + 18 + 1 + + + RSYNC + Launch regular conversion synchronously + with DFSDM0 + 19 + 1 + + + RDMAEN + DMA channel enabled to read data for the + regular conversion + 21 + 1 + + + RCH + Regular channel selection + 24 + 3 + + + FAST + Fast conversion mode selection for + regular conversions + 29 + 1 + + + AWFSEL + Analog watchdog fast mode + select + 30 + 1 + + + + + DFSDM0_CR2 + DFSDM0_CR2 + DFSDM control register 2 + 0xB0 + 0x20 + read-write + 0x00000000 + + + JEOCIE + Injected end of conversion interrupt + enable + 0 + 1 + + + REOCIE + Regular end of conversion interrupt + enable + 1 + 1 + + + JOVRIE + Injected data overrun interrupt + enable + 2 + 1 + + + ROVRIE + Regular data overrun interrupt + enable + 3 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 4 + 1 + + + SCDIE + Short-circuit detector interrupt + enable + 5 + 1 + + + CKABIE + Clock absence interrupt + enable + 6 + 1 + + + EXCH + Extremes detector channel + selection + 8 + 8 + + + AWDCH + Analog watchdog channel + selection + 16 + 8 + + + + + DFSDM1_CR2 + DFSDM1_CR2 + DFSDM control register 2 + 0xB4 + 0x20 + read-write + 0x00000000 + + + JEOCIE + Injected end of conversion interrupt + enable + 0 + 1 + + + REOCIE + Regular end of conversion interrupt + enable + 1 + 1 + + + JOVRIE + Injected data overrun interrupt + enable + 2 + 1 + + + ROVRIE + Regular data overrun interrupt + enable + 3 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 4 + 1 + + + SCDIE + Short-circuit detector interrupt + enable + 5 + 1 + + + CKABIE + Clock absence interrupt + enable + 6 + 1 + + + EXCH + Extremes detector channel + selection + 8 + 8 + + + AWDCH + Analog watchdog channel + selection + 16 + 8 + + + + + DFSDM2_CR2 + DFSDM2_CR2 + DFSDM control register 2 + 0xB8 + 0x20 + read-write + 0x00000000 + + + JEOCIE + Injected end of conversion interrupt + enable + 0 + 1 + + + REOCIE + Regular end of conversion interrupt + enable + 1 + 1 + + + JOVRIE + Injected data overrun interrupt + enable + 2 + 1 + + + ROVRIE + Regular data overrun interrupt + enable + 3 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 4 + 1 + + + SCDIE + Short-circuit detector interrupt + enable + 5 + 1 + + + CKABIE + Clock absence interrupt + enable + 6 + 1 + + + EXCH + Extremes detector channel + selection + 8 + 8 + + + AWDCH + Analog watchdog channel + selection + 16 + 8 + + + + + DFSDM3_CR2 + DFSDM3_CR2 + DFSDM control register 2 + 0xBC + 0x20 + read-write + 0x00000000 + + + JEOCIE + Injected end of conversion interrupt + enable + 0 + 1 + + + REOCIE + Regular end of conversion interrupt + enable + 1 + 1 + + + JOVRIE + Injected data overrun interrupt + enable + 2 + 1 + + + ROVRIE + Regular data overrun interrupt + enable + 3 + 1 + + + AWDIE + Analog watchdog interrupt + enable + 4 + 1 + + + SCDIE + Short-circuit detector interrupt + enable + 5 + 1 + + + CKABIE + Clock absence interrupt + enable + 6 + 1 + + + EXCH + Extremes detector channel + selection + 8 + 8 + + + AWDCH + Analog watchdog channel + selection + 16 + 8 + + + + + DFSDM0_ISR + DFSDM0_ISR + DFSDM interrupt and status + register + 0xC0 + 0x20 + read-only + 0x00000000 + + + JEOCF + End of injected conversion + flag + 0 + 1 + + + REOCF + End of regular conversion + flag + 1 + 1 + + + JOVRF + Injected conversion overrun + flag + 2 + 1 + + + ROVRF + Regular conversion overrun + flag + 3 + 1 + + + AWDF + Analog watchdog + 4 + 1 + + + JCIP + Injected conversion in progress + status + 13 + 1 + + + RCIP + Regular conversion in progress + status + 14 + 1 + + + CKABF + Clock absence flag + 16 + 8 + + + SCDF + short-circuit detector + flag + 24 + 8 + + + + + DFSDM1_ISR + DFSDM1_ISR + DFSDM interrupt and status + register + 0xC4 + 0x20 + read-only + 0x00000000 + + + JEOCF + End of injected conversion + flag + 0 + 1 + + + REOCF + End of regular conversion + flag + 1 + 1 + + + JOVRF + Injected conversion overrun + flag + 2 + 1 + + + ROVRF + Regular conversion overrun + flag + 3 + 1 + + + AWDF + Analog watchdog + 4 + 1 + + + JCIP + Injected conversion in progress + status + 13 + 1 + + + RCIP + Regular conversion in progress + status + 14 + 1 + + + CKABF + Clock absence flag + 16 + 8 + + + SCDF + short-circuit detector + flag + 24 + 8 + + + + + DFSDM2_ISR + DFSDM2_ISR + DFSDM interrupt and status + register + 0xC8 + 0x20 + read-only + 0x00000000 + + + JEOCF + End of injected conversion + flag + 0 + 1 + + + REOCF + End of regular conversion + flag + 1 + 1 + + + JOVRF + Injected conversion overrun + flag + 2 + 1 + + + ROVRF + Regular conversion overrun + flag + 3 + 1 + + + AWDF + Analog watchdog + 4 + 1 + + + JCIP + Injected conversion in progress + status + 13 + 1 + + + RCIP + Regular conversion in progress + status + 14 + 1 + + + CKABF + Clock absence flag + 16 + 8 + + + SCDF + short-circuit detector + flag + 24 + 8 + + + + + DFSDM3_ISR + DFSDM3_ISR + DFSDM interrupt and status + register + 0xCC + 0x20 + read-only + 0x00000000 + + + JEOCF + End of injected conversion + flag + 0 + 1 + + + REOCF + End of regular conversion + flag + 1 + 1 + + + JOVRF + Injected conversion overrun + flag + 2 + 1 + + + ROVRF + Regular conversion overrun + flag + 3 + 1 + + + AWDF + Analog watchdog + 4 + 1 + + + JCIP + Injected conversion in progress + status + 13 + 1 + + + RCIP + Regular conversion in progress + status + 14 + 1 + + + CKABF + Clock absence flag + 16 + 8 + + + SCDF + short-circuit detector + flag + 24 + 8 + + + + + DFSDM0_ICR + DFSDM0_ICR + DFSDM interrupt flag clear + register + 0xD0 + 0x20 + read-write + 0x00000000 + + + CLRJOVRF + Clear the injected conversion overrun + flag + 2 + 1 + + + CLRROVRF + Clear the regular conversion overrun + flag + 3 + 1 + + + CLRCKABF + Clear the clock absence + flag + 16 + 8 + + + CLRSCDF + Clear the short-circuit detector + flag + 24 + 8 + + + + + DFSDM1_ICR + DFSDM1_ICR + DFSDM interrupt flag clear + register + 0xD4 + 0x20 + read-write + 0x00000000 + + + CLRJOVRF + Clear the injected conversion overrun + flag + 2 + 1 + + + CLRROVRF + Clear the regular conversion overrun + flag + 3 + 1 + + + CLRCKABF + Clear the clock absence + flag + 16 + 8 + + + CLRSCDF + Clear the short-circuit detector + flag + 24 + 8 + + + + + DFSDM2_ICR + DFSDM2_ICR + DFSDM interrupt flag clear + register + 0xD8 + 0x20 + read-write + 0x00000000 + + + CLRJOVRF + Clear the injected conversion overrun + flag + 2 + 1 + + + CLRROVRF + Clear the regular conversion overrun + flag + 3 + 1 + + + CLRCKABF + Clear the clock absence + flag + 16 + 8 + + + CLRSCDF + Clear the short-circuit detector + flag + 24 + 8 + + + + + DFSDM3_ICR + DFSDM3_ICR + DFSDM interrupt flag clear + register + 0xDC + 0x20 + read-write + 0x00000000 + + + CLRJOVRF + Clear the injected conversion overrun + flag + 2 + 1 + + + CLRROVRF + Clear the regular conversion overrun + flag + 3 + 1 + + + CLRCKABF + Clear the clock absence + flag + 16 + 8 + + + CLRSCDF + Clear the short-circuit detector + flag + 24 + 8 + + + + + DFSDM0_JCHGR + DFSDM0_JCHGR + DFSDM injected channel group selection + register + 0xE0 + 0x20 + read-write + 0x00000000 + + + JCHG + Injected channel group + selection + 0 + 8 + + + + + DFSDM1_JCHGR + DFSDM1_JCHGR + DFSDM injected channel group selection + register + 0xE4 + 0x20 + read-write + 0x00000000 + + + JCHG + Injected channel group + selection + 0 + 8 + + + + + DFSDM2_JCHGR + DFSDM2_JCHGR + DFSDM injected channel group selection + register + 0xE8 + 0x20 + read-write + 0x00000000 + + + JCHG + Injected channel group + selection + 0 + 8 + + + + + DFSDM3_JCHGR + DFSDM3_JCHGR + DFSDM injected channel group selection + register + 0xEC + 0x20 + read-write + 0x00000000 + + + JCHG + Injected channel group + selection + 0 + 8 + + + + + DFSDM0_FCR + DFSDM0_FCR + DFSDM filter control register + 0xF0 + 0x20 + read-write + 0x00000000 + + + IOSR + Integrator oversampling ratio (averaging + length) + 0 + 8 + + + FOSR + Sinc filter oversampling ratio + (decimation rate) + 16 + 10 + + + FORD + Sinc filter order + 29 + 3 + + + + + DFSDM1_FCR + DFSDM1_FCR + DFSDM filter control register + 0xF4 + 0x20 + read-write + 0x00000000 + + + IOSR + Integrator oversampling ratio (averaging + length) + 0 + 8 + + + FOSR + Sinc filter oversampling ratio + (decimation rate) + 16 + 10 + + + FORD + Sinc filter order + 29 + 3 + + + + + DFSDM2_FCR + DFSDM2_FCR + DFSDM filter control register + 0xF8 + 0x20 + read-write + 0x00000000 + + + IOSR + Integrator oversampling ratio (averaging + length) + 0 + 8 + + + FOSR + Sinc filter oversampling ratio + (decimation rate) + 16 + 10 + + + FORD + Sinc filter order + 29 + 3 + + + + + DFSDM3_FCR + DFSDM3_FCR + DFSDM filter control register + 0xFC + 0x20 + read-write + 0x00000000 + + + IOSR + Integrator oversampling ratio (averaging + length) + 0 + 8 + + + FOSR + Sinc filter oversampling ratio + (decimation rate) + 16 + 10 + + + FORD + Sinc filter order + 29 + 3 + + + + + DFSDM0_JDATAR + DFSDM0_JDATAR + DFSDM data register for injected + group + 0x100 + 0x20 + read-only + 0x00000000 + + + JDATACH + Injected channel most recently + converted + 0 + 3 + + + JDATA + Injected group conversion + data + 8 + 24 + + + + + DFSDM1_JDATAR + DFSDM1_JDATAR + DFSDM data register for injected + group + 0x104 + 0x20 + read-only + 0x00000000 + + + JDATACH + Injected channel most recently + converted + 0 + 3 + + + JDATA + Injected group conversion + data + 8 + 24 + + + + + DFSDM2_JDATAR + DFSDM2_JDATAR + DFSDM data register for injected + group + 0x108 + 0x20 + read-only + 0x00000000 + + + JDATACH + Injected channel most recently + converted + 0 + 3 + + + JDATA + Injected group conversion + data + 8 + 24 + + + + + DFSDM3_JDATAR + DFSDM3_JDATAR + DFSDM data register for injected + group + 0x10C + 0x20 + read-only + 0x00000000 + + + JDATACH + Injected channel most recently + converted + 0 + 3 + + + JDATA + Injected group conversion + data + 8 + 24 + + + + + DFSDM0_RDATAR + DFSDM0_RDATAR + DFSDM data register for the regular + channel + 0x110 + 0x20 + read-only + 0x00000000 + + + RDATACH + Regular channel most recently + converted + 0 + 3 + + + RPEND + Regular channel pending + data + 4 + 1 + + + RDATA + Regular channel conversion + data + 8 + 24 + + + + + DFSDM1_RDATAR + DFSDM1_RDATAR + DFSDM data register for the regular + channel + 0x114 + 0x20 + read-only + 0x00000000 + + + RDATACH + Regular channel most recently + converted + 0 + 3 + + + RPEND + Regular channel pending + data + 4 + 1 + + + RDATA + Regular channel conversion + data + 8 + 24 + + + + + DFSDM2_RDATAR + DFSDM2_RDATAR + DFSDM data register for the regular + channel + 0x118 + 0x20 + read-only + 0x00000000 + + + RDATACH + Regular channel most recently + converted + 0 + 3 + + + RPEND + Regular channel pending + data + 4 + 1 + + + RDATA + Regular channel conversion + data + 8 + 24 + + + + + DFSDM3_RDATAR + DFSDM3_RDATAR + DFSDM data register for the regular + channel + 0x11C + 0x20 + read-only + 0x00000000 + + + RDATACH + Regular channel most recently + converted + 0 + 3 + + + RPEND + Regular channel pending + data + 4 + 1 + + + RDATA + Regular channel conversion + data + 8 + 24 + + + + + DFSDM0_AWHTR + DFSDM0_AWHTR + DFSDM analog watchdog high threshold + register + 0x120 + 0x20 + read-write + 0x00000000 + + + BKAWH + Break signal assignment to analog + watchdog high threshold event + 0 + 4 + + + AWHT + Analog watchdog high + threshold + 8 + 24 + + + + + DFSDM1_AWHTR + DFSDM1_AWHTR + DFSDM analog watchdog high threshold + register + 0x124 + 0x20 + read-write + 0x00000000 + + + BKAWH + Break signal assignment to analog + watchdog high threshold event + 0 + 4 + + + AWHT + Analog watchdog high + threshold + 8 + 24 + + + + + DFSDM2_AWHTR + DFSDM2_AWHTR + DFSDM analog watchdog high threshold + register + 0x128 + 0x20 + read-write + 0x00000000 + + + BKAWH + Break signal assignment to analog + watchdog high threshold event + 0 + 4 + + + AWHT + Analog watchdog high + threshold + 8 + 24 + + + + + DFSDM3_AWHTR + DFSDM3_AWHTR + DFSDM analog watchdog high threshold + register + 0x12C + 0x20 + read-write + 0x00000000 + + + BKAWH + Break signal assignment to analog + watchdog high threshold event + 0 + 4 + + + AWHT + Analog watchdog high + threshold + 8 + 24 + + + + + DFSDM0_AWLTR + DFSDM0_AWLTR + DFSDM analog watchdog low threshold + register + 0x130 + 0x20 + read-write + 0x00000000 + + + BKAWL + Break signal assignment to analog + watchdog low threshold event + 0 + 4 + + + AWLT + Analog watchdog low + threshold + 8 + 24 + + + + + DFSDM1_AWLTR + DFSDM1_AWLTR + DFSDM analog watchdog low threshold + register + 0x134 + 0x20 + read-write + 0x00000000 + + + BKAWL + Break signal assignment to analog + watchdog low threshold event + 0 + 4 + + + AWLT + Analog watchdog low + threshold + 8 + 24 + + + + + DFSDM2_AWLTR + DFSDM2_AWLTR + DFSDM analog watchdog low threshold + register + 0x138 + 0x20 + read-write + 0x00000000 + + + BKAWL + Break signal assignment to analog + watchdog low threshold event + 0 + 4 + + + AWLT + Analog watchdog low + threshold + 8 + 24 + + + + + DFSDM3_AWLTR + DFSDM3_AWLTR + DFSDM analog watchdog low threshold + register + 0x13C + 0x20 + read-write + 0x00000000 + + + BKAWL + Break signal assignment to analog + watchdog low threshold event + 0 + 4 + + + AWLT + Analog watchdog low + threshold + 8 + 24 + + + + + DFSDM0_AWSR + DFSDM0_AWSR + DFSDM analog watchdog status + register + 0x140 + 0x20 + read-only + 0x00000000 + + + AWLTF + Analog watchdog low threshold + flag + 0 + 8 + + + AWHTF + Analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM1_AWSR + DFSDM1_AWSR + DFSDM analog watchdog status + register + 0x144 + 0x20 + read-only + 0x00000000 + + + AWLTF + Analog watchdog low threshold + flag + 0 + 8 + + + AWHTF + Analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM2_AWSR + DFSDM2_AWSR + DFSDM analog watchdog status + register + 0x148 + 0x20 + read-only + 0x00000000 + + + AWLTF + Analog watchdog low threshold + flag + 0 + 8 + + + AWHTF + Analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM3_AWSR + DFSDM3_AWSR + DFSDM analog watchdog status + register + 0x14C + 0x20 + read-only + 0x00000000 + + + AWLTF + Analog watchdog low threshold + flag + 0 + 8 + + + AWHTF + Analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM0_AWCFR + DFSDM0_AWCFR + DFSDM analog watchdog clear flag + register + 0x150 + 0x20 + read-write + 0x00000000 + + + CLRAWLTF + Clear the analog watchdog low threshold + flag + 0 + 8 + + + CLRAWHTF + Clear the analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM1_AWCFR + DFSDM1_AWCFR + DFSDM analog watchdog clear flag + register + 0x154 + 0x20 + read-write + 0x00000000 + + + CLRAWLTF + Clear the analog watchdog low threshold + flag + 0 + 8 + + + CLRAWHTF + Clear the analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM2_AWCFR + DFSDM2_AWCFR + DFSDM analog watchdog clear flag + register + 0x158 + 0x20 + read-write + 0x00000000 + + + CLRAWLTF + Clear the analog watchdog low threshold + flag + 0 + 8 + + + CLRAWHTF + Clear the analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM3_AWCFR + DFSDM3_AWCFR + DFSDM analog watchdog clear flag + register + 0x15C + 0x20 + read-write + 0x00000000 + + + CLRAWLTF + Clear the analog watchdog low threshold + flag + 0 + 8 + + + CLRAWHTF + Clear the analog watchdog high threshold + flag + 8 + 8 + + + + + DFSDM0_EXMAX + DFSDM0_EXMAX + DFSDM Extremes detector maximum + register + 0x160 + 0x20 + read-only + 0x00000000 + + + EXMAXCH + Extremes detector maximum data + channel + 0 + 3 + + + EXMAX + Extremes detector maximum + value + 8 + 24 + + + + + DFSDM1_EXMAX + DFSDM1_EXMAX + DFSDM Extremes detector maximum + register + 0x164 + 0x20 + read-only + 0x00000000 + + + EXMAXCH + Extremes detector maximum data + channel + 0 + 3 + + + EXMAX + Extremes detector maximum + value + 8 + 24 + + + + + DFSDM2_EXMAX + DFSDM2_EXMAX + DFSDM Extremes detector maximum + register + 0x168 + 0x20 + read-only + 0x00000000 + + + EXMAXCH + Extremes detector maximum data + channel + 0 + 3 + + + EXMAX + Extremes detector maximum + value + 8 + 24 + + + + + DFSDM3_EXMAX + DFSDM3_EXMAX + DFSDM Extremes detector maximum + register + 0x16C + 0x20 + read-only + 0x00000000 + + + EXMAXCH + Extremes detector maximum data + channel + 0 + 3 + + + EXMAX + Extremes detector maximum + value + 8 + 24 + + + + + DFSDM0_EXMIN + DFSDM0_EXMIN + DFSDM Extremes detector minimum + register + 0x170 + 0x20 + read-only + 0x00000000 + + + EXMINCH + Extremes detector minimum data + channel + 0 + 3 + + + EXMIN + Extremes detector minimum + value + 8 + 24 + + + + + DFSDM1_EXMIN + DFSDM1_EXMIN + DFSDM Extremes detector minimum + register + 0x174 + 0x20 + read-only + 0x00000000 + + + EXMINCH + Extremes detector minimum data + channel + 0 + 3 + + + EXMIN + Extremes detector minimum + value + 8 + 24 + + + + + DFSDM2_EXMIN + DFSDM2_EXMIN + DFSDM Extremes detector minimum + register + 0x178 + 0x20 + read-only + 0x00000000 + + + EXMINCH + Extremes detector minimum data + channel + 0 + 3 + + + EXMIN + Extremes detector minimum + value + 8 + 24 + + + + + DFSDM3_EXMIN + DFSDM3_EXMIN + DFSDM Extremes detector minimum + register + 0x17C + 0x20 + read-only + 0x00000000 + + + EXMINCH + Extremes detector minimum data + channel + 0 + 3 + + + EXMIN + Extremes detector minimum + value + 8 + 24 + + + + + DFSDM0_CNVTIMR + DFSDM0_CNVTIMR + DFSDM conversion timer + register + 0x180 + 0x20 + read-only + 0x00000000 + + + CNVCNT + 28-bit timer counting conversion + time + 4 + 28 + + + + + DFSDM1_CNVTIMR + DFSDM1_CNVTIMR + DFSDM conversion timer + register + 0x184 + 0x20 + read-only + 0x00000000 + + + CNVCNT + 28-bit timer counting conversion + time + 4 + 28 + + + + + DFSDM2_CNVTIMR + DFSDM2_CNVTIMR + DFSDM conversion timer + register + 0x188 + 0x20 + read-only + 0x00000000 + + + CNVCNT + 28-bit timer counting conversion + time + 4 + 28 + + + + + DFSDM3_CNVTIMR + DFSDM3_CNVTIMR + DFSDM conversion timer + register + 0x18C + 0x20 + read-only + 0x00000000 + + + CNVCNT + 28-bit timer counting conversion + time + 4 + 28 + + + + + + + TIM16 + General-purpose-timers + TIMs + 0x40014400 + + 0x0 + 0x400 + registers + + + TIM16 + TIM16 global interrupt + 117 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1M_3 + Output Compare 1 mode + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + TIM16_AF1 + TIM16_AF1 + TIM16 alternate function register + 1 + 0x60 + 0x20 + read-write + 0x0000 + + + BKINE + BRK BKIN input enable + 0 + 1 + + + BKCMP1E + BRK COMP1 enable + 1 + 1 + + + BKCMP2E + BRK COMP2 enable + 2 + 1 + + + BKDFBK1E + BRK dfsdm1_break[1] enable + 8 + 1 + + + BKINP + BRK BKIN input polarity + 9 + 1 + + + BKCMP1P + BRK COMP1 input polarity + 10 + 1 + + + BKCMP2P + BRK COMP2 input polarity + 11 + 1 + + + + + TIM16_TISEL + TIM16_TISEL + TIM16 input selection register + 0x68 + 0x20 + read-write + 0x0000 + + + TI1SEL + selects TI1[0] to TI1[15] + input + 0 + 4 + + + + + + + TIM17 + General-purpose-timers + TIMs + 0x40014800 + + 0x0 + 0x400 + registers + + + TIM17 + TIM17 global interrupt + 118 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1M_3 + Output Compare 1 mode + 16 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF Copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + TIM17_AF1 + TIM17_AF1 + TIM17 alternate function register + 1 + 0x60 + 0x20 + read-write + 0x0000 + + + BKINE + BRK BKIN input enable + 0 + 1 + + + BKCMP1E + BRK COMP1 enable + 1 + 1 + + + BKCMP2E + BRK COMP2 enable + 2 + 1 + + + BKDFBK1E + BRK dfsdm1_break[1] enable + 8 + 1 + + + BKINP + BRK BKIN input polarity + 9 + 1 + + + BKCMP1P + BRK COMP1 input polarity + 10 + 1 + + + BKCMP2P + BRK COMP2 input polarity + 11 + 1 + + + + + TIM17_TISEL + TIM17_TISEL + TIM17 input selection register + 0x68 + 0x20 + read-write + 0x0000 + + + TI1SEL + selects TI1[0] to TI1[15] + input + 0 + 4 + + + + + + + TIM15 + General purpose timers + TIMs + 0x40014000 + + 0x0 + 0x400 + registers + + + TIM15 + TIM15 global interrupt + 116 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + MMS + Master mode selection + 4 + 3 + + + TI1S + TI1 selection + 7 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS_2_0 + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + SMS_3 + Slave mode selection bit 3 + 16 + 1 + + + TS_4_3 + Trigger selection - bit + 4:3 + 20 + 2 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UIE + Update interrupt enable + 0 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + TDE + Trigger DMA request enable + 14 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + BG + Break generation + 7 + 1 + + + TG + Trigger generation + 6 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC1M_3 + Output Compare 1 mode bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PSC + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + IC1PSC + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + MOE + Main output enable + 15 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + BKP + Break polarity + 13 + 1 + + + BKE + Break enable + 12 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + LOCK + Lock configuration + 8 + 2 + + + DTG + Dead-time generator setup + 0 + 8 + + + BKF + Break filter + 16 + 4 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + AF1 + AF1 + TIM15 alternate fdfsdm1_breakon register + 1 + 0x60 + 0x20 + read-write + 0x0000 + + + BKINE + BRK BKIN input enable + 0 + 1 + + + BKCMP1E + BRK COMP1 enable + 1 + 1 + + + BKCMP2E + BRK COMP2 enable + 2 + 1 + + + BKDF1BK0E + BRK dfsdm1_break[0] enable + 8 + 1 + + + BKINP + BRK BKIN input polarity + 9 + 1 + + + BKCMP1P + BRK COMP1 input polarity + 10 + 1 + + + BKCMP2P + BRK COMP2 input polarity + 11 + 1 + + + + + TISEL + TISEL + TIM15 input selection register + 0x68 + 0x20 + read-write + 0x0000 + + + TI1SEL + selects TI1[0] to TI1[15] + input + 0 + 4 + + + TI2SEL + selects TI2[0] to TI2[15] + input + 8 + 4 + + + + + + + USART1 + Universal synchronous asynchronous receiver + transmitter + USART + 0x40011000 + + 0x0 + 0x400 + registers + + + + CR1 + CR1 + Control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + RXFFIE + RXFIFO Full interrupt + enable + 31 + 1 + + + TXFEIE + TXFIFO empty interrupt + enable + 30 + 1 + + + FIFOEN + FIFO mode enable + 29 + 1 + + + M1 + Word length + 28 + 1 + + + EOBIE + End of Block interrupt + enable + 27 + 1 + + + RTOIE + Receiver timeout interrupt + enable + 26 + 1 + + + DEAT4 + Driver Enable assertion + time + 25 + 1 + + + DEAT3 + DEAT3 + 24 + 1 + + + DEAT2 + DEAT2 + 23 + 1 + + + DEAT1 + DEAT1 + 22 + 1 + + + DEAT0 + DEAT0 + 21 + 1 + + + DEDT4 + Driver Enable de-assertion + time + 20 + 1 + + + DEDT3 + DEDT3 + 19 + 1 + + + DEDT2 + DEDT2 + 18 + 1 + + + DEDT1 + DEDT1 + 17 + 1 + + + DEDT0 + DEDT0 + 16 + 1 + + + OVER8 + Oversampling mode + 15 + 1 + + + CMIE + Character match interrupt + enable + 14 + 1 + + + MME + Mute mode enable + 13 + 1 + + + M0 + Word length + 12 + 1 + + + WAKE + Receiver wakeup method + 11 + 1 + + + PCE + Parity control enable + 10 + 1 + + + PS + Parity selection + 9 + 1 + + + PEIE + PE interrupt enable + 8 + 1 + + + TXEIE + interrupt enable + 7 + 1 + + + TCIE + Transmission complete interrupt + enable + 6 + 1 + + + RXNEIE + RXNE interrupt enable + 5 + 1 + + + IDLEIE + IDLE interrupt enable + 4 + 1 + + + TE + Transmitter enable + 3 + 1 + + + RE + Receiver enable + 2 + 1 + + + UESM + USART enable in Stop mode + 1 + 1 + + + UE + USART enable + 0 + 1 + + + + + CR2 + CR2 + Control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + ADD4_7 + Address of the USART node + 28 + 4 + + + ADD0_3 + Address of the USART node + 24 + 4 + + + RTOEN + Receiver timeout enable + 23 + 1 + + + ABRMOD1 + Auto baud rate mode + 22 + 1 + + + ABRMOD0 + ABRMOD0 + 21 + 1 + + + ABREN + Auto baud rate enable + 20 + 1 + + + MSBFIRST + Most significant bit first + 19 + 1 + + + TAINV + Binary data inversion + 18 + 1 + + + TXINV + TX pin active level + inversion + 17 + 1 + + + RXINV + RX pin active level + inversion + 16 + 1 + + + SWAP + Swap TX/RX pins + 15 + 1 + + + LINEN + LIN mode enable + 14 + 1 + + + STOP + STOP bits + 12 + 2 + + + CLKEN + Clock enable + 11 + 1 + + + CPOL + Clock polarity + 10 + 1 + + + CPHA + Clock phase + 9 + 1 + + + LBCL + Last bit clock pulse + 8 + 1 + + + LBDIE + LIN break detection interrupt + enable + 6 + 1 + + + LBDL + LIN break detection length + 5 + 1 + + + ADDM7 + 7-bit Address Detection/4-bit Address + Detection + 4 + 1 + + + DIS_NSS + When the DSI_NSS bit is set, the NSS pin + input is ignored + 3 + 1 + + + SLVEN + Synchronous Slave mode + enable + 0 + 1 + + + + + CR3 + CR3 + Control register 3 + 0x8 + 0x20 + read-write + 0x0000 + + + TXFTCFG + TXFIFO threshold + configuration + 29 + 3 + + + RXFTIE + RXFIFO threshold interrupt + enable + 28 + 1 + + + RXFTCFG + Receive FIFO threshold + configuration + 25 + 3 + + + TCBGTIE + Transmission Complete before guard time, + interrupt enable + 24 + 1 + + + TXFTIE + TXFIFO threshold interrupt + enable + 23 + 1 + + + WUFIE + Wakeup from Stop mode interrupt + enable + 22 + 1 + + + WUS + Wakeup from Stop mode interrupt flag + selection + 20 + 2 + + + SCARCNT + Smartcard auto-retry count + 17 + 3 + + + DEP + Driver enable polarity + selection + 15 + 1 + + + DEM + Driver enable mode + 14 + 1 + + + DDRE + DMA Disable on Reception + Error + 13 + 1 + + + OVRDIS + Overrun Disable + 12 + 1 + + + ONEBIT + One sample bit method + enable + 11 + 1 + + + CTSIE + CTS interrupt enable + 10 + 1 + + + CTSE + CTS enable + 9 + 1 + + + RTSE + RTS enable + 8 + 1 + + + DMAT + DMA enable transmitter + 7 + 1 + + + DMAR + DMA enable receiver + 6 + 1 + + + SCEN + Smartcard mode enable + 5 + 1 + + + NACK + Smartcard NACK enable + 4 + 1 + + + HDSEL + Half-duplex selection + 3 + 1 + + + IRLP + Ir low-power + 2 + 1 + + + IREN + Ir mode enable + 1 + 1 + + + EIE + Error interrupt enable + 0 + 1 + + + + + BRR + BRR + Baud rate register + 0xC + 0x20 + read-write + 0x0000 + + + BRR_4_15 + DIV_Mantissa + 4 + 12 + + + BRR_0_3 + DIV_Fraction + 0 + 4 + + + + + GTPR + GTPR + Guard time and prescaler + register + 0x10 + 0x20 + read-write + 0x0000 + + + GT + Guard time value + 8 + 8 + + + PSC + Prescaler value + 0 + 8 + + + + + RTOR + RTOR + Receiver timeout register + 0x14 + 0x20 + read-write + 0x0000 + + + BLEN + Block Length + 24 + 8 + + + RTO + Receiver timeout value + 0 + 24 + + + + + RQR + RQR + Request register + 0x18 + 0x20 + write-only + 0x0000 + + + TXFRQ + Transmit data flush + request + 4 + 1 + + + RXFRQ + Receive data flush request + 3 + 1 + + + MMRQ + Mute mode request + 2 + 1 + + + SBKRQ + Send break request + 1 + 1 + + + ABRRQ + Auto baud rate request + 0 + 1 + + + + + ISR + ISR + Interrupt & status + register + 0x1C + 0x20 + read-only + 0x00C0 + + + TXFT + TXFIFO threshold flag + 27 + 1 + + + RXFT + RXFIFO threshold flag + 26 + 1 + + + TCBGT + Transmission complete before guard time + flag + 25 + 1 + + + RXFF + RXFIFO Full + 24 + 1 + + + TXFE + TXFIFO Empty + 23 + 1 + + + REACK + REACK + 22 + 1 + + + TEACK + TEACK + 21 + 1 + + + WUF + WUF + 20 + 1 + + + RWU + RWU + 19 + 1 + + + SBKF + SBKF + 18 + 1 + + + CMF + CMF + 17 + 1 + + + BUSY + BUSY + 16 + 1 + + + ABRF + ABRF + 15 + 1 + + + ABRE + ABRE + 14 + 1 + + + UDR + SPI slave underrun error + flag + 13 + 1 + + + EOBF + EOBF + 12 + 1 + + + RTOF + RTOF + 11 + 1 + + + CTS + CTS + 10 + 1 + + + CTSIF + CTSIF + 9 + 1 + + + LBDF + LBDF + 8 + 1 + + + TXE + TXE + 7 + 1 + + + TC + TC + 6 + 1 + + + RXNE + RXNE + 5 + 1 + + + IDLE + IDLE + 4 + 1 + + + ORE + ORE + 3 + 1 + + + NF + NF + 2 + 1 + + + FE + FE + 1 + 1 + + + PE + PE + 0 + 1 + + + + + ICR + ICR + Interrupt flag clear register + 0x20 + 0x20 + write-only + 0x0000 + + + WUCF + Wakeup from Stop mode clear + flag + 20 + 1 + + + CMCF + Character match clear flag + 17 + 1 + + + UDRCF + SPI slave underrun clear + flag + 13 + 1 + + + EOBCF + End of block clear flag + 12 + 1 + + + RTOCF + Receiver timeout clear + flag + 11 + 1 + + + CTSCF + CTS clear flag + 9 + 1 + + + LBDCF + LIN break detection clear + flag + 8 + 1 + + + TCBGTC + Transmission complete before Guard time + clear flag + 7 + 1 + + + TCCF + Transmission complete clear + flag + 6 + 1 + + + TXFECF + TXFIFO empty clear flag + 5 + 1 + + + IDLECF + Idle line detected clear + flag + 4 + 1 + + + ORECF + Overrun error clear flag + 3 + 1 + + + NCF + Noise detected clear flag + 2 + 1 + + + FECF + Framing error clear flag + 1 + 1 + + + PECF + Parity error clear flag + 0 + 1 + + + + + RDR + RDR + Receive data register + 0x24 + 0x20 + read-only + 0x0000 + + + RDR + Receive data value + 0 + 9 + + + + + TDR + TDR + Transmit data register + 0x28 + 0x20 + read-write + 0x0000 + + + TDR + Transmit data value + 0 + 9 + + + + + PRESC + PRESC + USART prescaler register + 0x2C + 0x20 + read-write + 0x0000 + + + PRESCALER + Clock prescaler + 0 + 4 + + + + + + + USART2 + 0x40004400 + + USART1 + USART1 global interrupt + 37 + + + + USART3 + 0x40004800 + + USART2 + USART2 global interrupt + 38 + + + + UART4 + 0x40004C00 + + USART3 + USART3 global interrupt + 39 + + + UART4 + UART4 global interrupt + 52 + + + + UART5 + 0x40005000 + + UART5 + UART5 global interrupt + 53 + + + + USART6 + 0x40011400 + + USART6 + USART6 global interrupt + 71 + + + + UART7 + 0x40007800 + + UART7 + UART7 global interrupt + 82 + + + + UART8 + 0x40007C00 + + UART8 + UART8 global interrupt + 83 + + + + TIM1 + Advanced-timers + TIM + 0x40010000 + + 0x0 + 0x400 + registers + + + TIM1_BRK + TIM1 break interrupt + 24 + + + TIM1_UP + TIM1 update interrupt + 25 + + + TIM1_TRG_COM + TIM1 trigger and commutation + 26 + + + TIM_CC + TIM1 capture / compare + 27 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + CEN + Counter enable + 0 + 1 + + + UDIS + Update disable + 1 + 1 + + + URS + Update request source + 2 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + DIR + Direction + 4 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CKD + Clock division + 8 + 2 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS2 + Master mode selection 2 + 20 + 4 + + + OIS6 + Output Idle state 6 + 18 + 1 + + + OIS5 + Output Idle state 5 + 16 + 1 + + + OIS4 + Output Idle state 4 + 14 + 1 + + + OIS3N + Output Idle state 3 + 13 + 1 + + + OIS3 + Output Idle state 3 + 12 + 1 + + + OIS2N + Output Idle state 2 + 11 + 1 + + + OIS2 + Output Idle state 2 + 10 + 1 + + + OIS1N + Output Idle state 1 + 9 + 1 + + + OIS1 + Output Idle state 1 + 8 + 1 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + CCUS + Capture/compare control update + selection + 2 + 1 + + + CCPC + Capture/compare preloaded + control + 0 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + SMS + Slave mode selection + 0 + 3 + + + TS + Trigger selection + 4 + 3 + + + MSM + Master/Slave mode + 7 + 1 + + + ETF + External trigger filter + 8 + 4 + + + ETPS + External trigger prescaler + 12 + 2 + + + ECE + External clock enable + 14 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + SMS_3 + Slave mode selection - bit + 3 + 16 + 1 + + + TS_4_3 + Trigger selection - bit + 4:3 + 20 + 2 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + COMDE + COM DMA request enable + 13 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + BIE + Break interrupt enable + 7 + 1 + + + COMIE + COM interrupt enable + 5 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC6IF + Compare 6 interrupt flag + 17 + 1 + + + CC5IF + Compare 5 interrupt flag + 16 + 1 + + + SBIF + System Break interrupt + flag + 13 + 1 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + B2IF + Break 2 interrupt flag + 8 + 1 + + + BIF + Break interrupt flag + 7 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + COMIF + COM interrupt flag + 5 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + COMG + Capture/Compare control update + generation + 5 + 1 + + + TG + Trigger generation + 6 + 1 + + + BG + Break generation + 7 + 1 + + + B2G + Break 2 generation + 8 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + OC1FE + Output Compare 1 fast + enable + 2 + 1 + + + OC1PE + Output Compare 1 preload + enable + 3 + 1 + + + OC1M + Output Compare 1 mode + 4 + 3 + + + OC1CE + Output Compare 1 clear + enable + 7 + 1 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + OC2FE + Output Compare 2 fast + enable + 10 + 1 + + + OC2PE + Output Compare 2 preload + enable + 11 + 1 + + + OC2M + Output Compare 2 mode + 12 + 3 + + + OC2CE + Output Compare 2 clear + enable + 15 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + CC3S + Capture/Compare 3 + selection + 0 + 2 + + + OC3FE + Output compare 3 fast + enable + 2 + 1 + + + OC3PE + Output compare 3 preload + enable + 3 + 1 + + + OC3M + Output compare 3 mode + 4 + 3 + + + OC3CE + Output compare 3 clear + enable + 7 + 1 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + OC4FE + Output compare 4 fast + enable + 10 + 1 + + + OC4PE + Output compare 4 preload + enable + 11 + 1 + + + OC4M + Output compare 4 mode + 12 + 3 + + + OC4CE + Output compare 4 clear + enable + 15 + 1 + + + OC3M_3 + Output Compare 3 mode - bit + 3 + 16 + 1 + + + OC4M_4 + Output Compare 4 mode - bit + 3 + 24 + 1 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1NE + Capture/Compare 1 complementary output + enable + 2 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2NE + Capture/Compare 2 complementary output + enable + 6 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3NE + Capture/Compare 3 complementary output + enable + 10 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4NP + Capture/Compare 4 complementary output + polarity + 15 + 1 + + + CC5E + Capture/Compare 5 output + enable + 16 + 1 + + + CC5P + Capture/Compare 5 output + polarity + 17 + 1 + + + CC6E + Capture/Compare 6 output + enable + 20 + 1 + + + CC6P + Capture/Compare 6 output + polarity + 21 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + 0x00000000 + + + CNT + counter value + 0 + 16 + read-write + + + UIFCPY + UIF copy + 31 + 1 + read-only + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1 + Capture/Compare 1 value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2 + Capture/Compare 2 value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3 + Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4 + Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + RCR + RCR + repetition counter register + 0x30 + 0x20 + read-write + 0x0000 + + + REP + Repetition counter value + 0 + 8 + + + + + BDTR + BDTR + break and dead-time register + 0x44 + 0x20 + read-write + 0x0000 + + + DTG + Dead-time generator setup + 0 + 8 + + + LOCK + Lock configuration + 8 + 2 + + + OSSI + Off-state selection for Idle + mode + 10 + 1 + + + OSSR + Off-state selection for Run + mode + 11 + 1 + + + BKE + Break enable + 12 + 1 + + + BKP + Break polarity + 13 + 1 + + + AOE + Automatic output enable + 14 + 1 + + + MOE + Main output enable + 15 + 1 + + + BKF + Break filter + 16 + 4 + + + BK2F + Break 2 filter + 20 + 4 + + + BK2E + Break 2 enable + 24 + 1 + + + BK2P + Break 2 polarity + 25 + 1 + + + + + CCMR3_Output + CCMR3_Output + capture/compare mode register 3 (output + mode) + 0x54 + 0x20 + read-write + 0x0000 + + + OC5FE + Output compare 5 fast + enable + 2 + 1 + + + OC5PE + Output compare 5 preload + enable + 3 + 1 + + + OC5M + Output compare 5 mode + 4 + 3 + + + OC5CE + Output compare 5 clear + enable + 7 + 1 + + + OC6FE + Output compare 6 fast + enable + 10 + 1 + + + OC6PE + Output compare 6 preload + enable + 11 + 1 + + + OC6M + Output compare 6 mode + 12 + 3 + + + OC6CE + Output compare 6 clear + enable + 15 + 1 + + + OC5M3 + Output Compare 5 mode + 16 + 1 + + + OC6M3 + Output Compare 6 mode + 24 + 1 + + + + + CCR5 + CCR5 + capture/compare register 5 + 0x58 + 0x20 + read-write + 0x0000 + + + CCR5 + Capture/Compare 5 value + 0 + 16 + + + GC5C1 + Group Channel 5 and Channel + 1 + 29 + 1 + + + GC5C2 + Group Channel 5 and Channel + 2 + 30 + 1 + + + GC5C3 + Group Channel 5 and Channel + 3 + 31 + 1 + + + + + CRR6 + CRR6 + capture/compare register 6 + 0x5C + 0x20 + read-write + 0x0000 + + + CCR6 + Capture/Compare 6 value + 0 + 16 + + + + + AF1 + AF1 + TIM1 alternate function option register + 1 + 0x60 + 0x20 + read-write + 0x0000 + + + BKINE + BRK BKIN input enable + 0 + 1 + + + BKCMP1E + BRK COMP1 enable + 1 + 1 + + + BKCMP2E + BRK COMP2 enable + 2 + 1 + + + BKDF1BK0E + BRK dfsdm1_break[0] enable + 8 + 1 + + + BKINP + BRK BKIN input polarity + 9 + 1 + + + BKCMP1P + BRK COMP1 input polarity + 10 + 1 + + + BKCMP2P + BRK COMP2 input polarity + 11 + 1 + + + ETRSEL + ETR source selection + 14 + 4 + + + + + AF2 + AF2 + TIM1 Alternate function odfsdm1_breakster + 2 + 0x64 + 0x20 + read-write + 0x0000 + + + BK2INE + BRK2 BKIN input enable + 0 + 1 + + + BK2CMP1E + BRK2 COMP1 enable + 1 + 1 + + + BK2CMP2E + BRK2 COMP2 enable + 2 + 1 + + + BK2DF1BK1E + BRK2 dfsdm1_break[1] + enable + 8 + 1 + + + BK2INP + BRK2 BKIN2 input polarity + 9 + 1 + + + BK2CMP1P + BRK2 COMP1 input polarit + 10 + 1 + + + BK2CMP2P + BRK2 COMP2 input polarity + 11 + 1 + + + + + TISEL + TISEL + TIM1 timer input selection + register + 0x68 + 0x20 + read-write + 0x0000 + + + TI1SEL + selects TI1[0] to TI1[15] + input + 0 + 4 + + + TI2SEL + selects TI2[0] to TI2[15] + input + 8 + 4 + + + TI3SEL + selects TI3[0] to TI3[15] + input + 16 + 4 + + + TI4SEL + selects TI4[0] to TI4[15] + input + 24 + 4 + + + + + + + TIM8 + 0x40010400 + + TIM8_CC + TIM8 capture / compare + 46 + + + + FDCAN1 + FDCAN1 + FDCAN + 0x4000A000 + + 0x0 + 0x400 + registers + + + FDCAN1_IT0 + FDCAN1 Interrupt 0 + 19 + + + FDCAN1_IT1 + FDCAN1 Interrupt 1 + 21 + + + FDCAN_CAL + CAN2TX interrupts + 63 + + + + FDCAN_CREL + FDCAN_CREL + FDCAN Core Release Register + 0x0 + 0x20 + read-only + 0x00000000 + + + REL + Core release + 28 + 4 + + + STEP + Step of Core release + 24 + 4 + + + SUBSTEP + Sub-step of Core release + 20 + 4 + + + YEAR + Timestamp Year + 16 + 4 + + + MON + Timestamp Month + 8 + 8 + + + DAY + Timestamp Day + 0 + 8 + + + + + FDCAN_ENDN + FDCAN_ENDN + FDCAN Core Release Register + 0x4 + 0x20 + read-only + 0x00000000 + + + ETV + Endiannes Test Value + 0 + 32 + + + + + FDCAN_DBTP + FDCAN_DBTP + FDCAN Data Bit Timing and Prescaler + Register + 0xC + 0x20 + read-only + 0x00000000 + + + DSJW + Synchronization Jump Width + 0 + 4 + + + DTSEG2 + Data time segment after sample + point + 4 + 4 + + + DTSEG1 + Data time segment after sample + point + 8 + 5 + + + DBRP + Data BIt Rate Prescaler + 16 + 5 + + + TDC + Transceiver Delay + Compensation + 23 + 1 + + + + + FDCAN_TEST + FDCAN_TEST + FDCAN Test Register + 0x10 + 0x20 + read-only + 0x00000000 + + + LBCK + Loop Back mode + 4 + 1 + + + TX + Loop Back mode + 5 + 2 + + + RX + Control of Transmit Pin + 7 + 1 + + + + + FDCAN_RWD + FDCAN_RWD + FDCAN RAM Watchdog Register + 0x14 + 0x20 + read-only + 0x00000000 + + + WDV + Watchdog value + 8 + 8 + + + WDC + Watchdog configuration + 0 + 8 + + + + + FDCAN_CCCR + FDCAN_CCCR + FDCAN CC Control Register + 0x18 + 0x20 + read-write + 0x00000000 + + + INIT + Initialization + 0 + 1 + + + CCE + Configuration Change + Enable + 1 + 1 + + + ASM + ASM Restricted Operation + Mode + 2 + 1 + + + CSA + Clock Stop Acknowledge + 3 + 1 + + + CSR + Clock Stop Request + 4 + 1 + + + MON + Bus Monitoring Mode + 5 + 1 + + + DAR + Disable Automatic + Retransmission + 6 + 1 + + + TEST + Test Mode Enable + 7 + 1 + + + FDOE + FD Operation Enable + 8 + 1 + + + BSE + FDCAN Bit Rate Switching + 9 + 1 + + + PXHD + Protocol Exception Handling + Disable + 12 + 1 + + + EFBI + Edge Filtering during Bus + Integration + 13 + 1 + + + TXP + TXP + 14 + 1 + + + NISO + Non ISO Operation + 15 + 1 + + + + + FDCAN_NBTP + FDCAN_NBTP + FDCAN Nominal Bit Timing and Prescaler + Register + 0x1C + 0x20 + read-write + 0x00000000 + + + NSJW + NSJW: Nominal (Re)Synchronization Jump + Width + 25 + 7 + + + NBRP + Bit Rate Prescaler + 16 + 9 + + + NTSEG1 + Nominal Time segment before sample + point + 8 + 8 + + + TSEG2 + Nominal Time segment after sample + point + 0 + 7 + + + + + FDCAN_TSCC + FDCAN_TSCC + FDCAN Timestamp Counter Configuration + Register + 0x20 + 0x20 + read-write + 0x00000000 + + + TCP + Timestamp Counter + Prescaler + 16 + 4 + + + TSS + Timestamp Select + 0 + 2 + + + + + FDCAN_TSCV + FDCAN_TSCV + FDCAN Timestamp Counter Value + Register + 0x24 + 0x20 + read-write + 0x00000000 + + + TSC + Timestamp Counter + 0 + 16 + + + + + FDCAN_TOCC + FDCAN_TOCC + FDCAN Timeout Counter Configuration + Register + 0x28 + 0x20 + read-write + 0x00000000 + + + ETOC + Enable Timeout Counter + 0 + 1 + + + TOS + Timeout Select + 1 + 2 + + + TOP + Timeout Period + 16 + 16 + + + + + FDCAN_TOCV + FDCAN_TOCV + FDCAN Timeout Counter Value + Register + 0x2C + 0x20 + read-write + 0x00000000 + + + TOC + Timeout Counter + 0 + 16 + + + + + FDCAN_ECR + FDCAN_ECR + FDCAN Error Counter Register + 0x40 + 0x20 + read-write + 0x00000000 + + + CEL + AN Error Logging + 16 + 8 + + + RP + Receive Error Passive + 15 + 1 + + + TREC + Receive Error Counter + 8 + 7 + + + TEC + Transmit Error Counter + 0 + 8 + + + + + FDCAN_PSR + FDCAN_PSR + FDCAN Protocol Status Register + 0x44 + 0x20 + read-write + 0x00000000 + + + LEC + Last Error Code + 0 + 3 + + + ACT + Activity + 3 + 2 + + + EP + Error Passive + 5 + 1 + + + EW + Warning Status + 6 + 1 + + + BO + Bus_Off Status + 7 + 1 + + + DLEC + Data Last Error Code + 8 + 3 + + + RESI + ESI flag of last received FDCAN + Message + 11 + 1 + + + RBRS + BRS flag of last received FDCAN + Message + 12 + 1 + + + REDL + Received FDCAN Message + 13 + 1 + + + PXE + Protocol Exception Event + 14 + 1 + + + TDCV + Transmitter Delay Compensation + Value + 16 + 7 + + + + + FDCAN_TDCR + FDCAN_TDCR + FDCAN Transmitter Delay Compensation + Register + 0x48 + 0x20 + read-only + 0x00000000 + + + TDCF + Transmitter Delay Compensation Filter + Window Length + 0 + 7 + + + TDCO + Transmitter Delay Compensation + Offset + 8 + 7 + + + + + FDCAN_IR + FDCAN_IR + FDCAN Interrupt Register + 0x50 + 0x20 + read-only + 0x00000000 + + + RF0N + Rx FIFO 0 New Message + 0 + 1 + + + RF0W + Rx FIFO 0 Full + 1 + 1 + + + RF0F + Rx FIFO 0 Full + 2 + 1 + + + RF0L + Rx FIFO 0 Message Lost + 3 + 1 + + + RF1N + Rx FIFO 1 New Message + 4 + 1 + + + RF1W + Rx FIFO 1 Watermark + Reached + 5 + 1 + + + RF1F + Rx FIFO 1 Watermark + Reached + 6 + 1 + + + RF1L + Rx FIFO 1 Message Lost + 7 + 1 + + + HPM + High Priority Message + 8 + 1 + + + TC + Transmission Completed + 9 + 1 + + + TCF + Transmission Cancellation + Finished + 10 + 1 + + + TEF + Tx FIFO Empty + 11 + 1 + + + TEFN + Tx Event FIFO New Entry + 12 + 1 + + + TEFW + Tx Event FIFO Watermark + Reached + 13 + 1 + + + TEFF + Tx Event FIFO Full + 14 + 1 + + + TEFL + Tx Event FIFO Element Lost + 15 + 1 + + + TSW + Timestamp Wraparound + 16 + 1 + + + MRAF + Message RAM Access Failure + 17 + 1 + + + TOO + Timeout Occurred + 18 + 1 + + + DRX + Message stored to Dedicated Rx + Buffer + 19 + 1 + + + ELO + Error Logging Overflow + 22 + 1 + + + EP + Error Passive + 23 + 1 + + + EW + Warning Status + 24 + 1 + + + BO + Bus_Off Status + 25 + 1 + + + WDI + Watchdog Interrupt + 26 + 1 + + + PEA + Protocol Error in Arbitration Phase + (Nominal Bit Time is used) + 27 + 1 + + + PED + Protocol Error in Data Phase (Data Bit + Time is used) + 28 + 1 + + + ARA + Access to Reserved Address + 29 + 1 + + + + + FDCAN_IE + FDCAN_IE + FDCAN Interrupt Enable + Register + 0x54 + 0x20 + read-only + 0x00000000 + + + RF0NE + Rx FIFO 0 New Message + Enable + 0 + 1 + + + RF0WE + Rx FIFO 0 Full Enable + 1 + 1 + + + RF0FE + Rx FIFO 0 Full Enable + 2 + 1 + + + RF0LE + Rx FIFO 0 Message Lost + Enable + 3 + 1 + + + RF1NE + Rx FIFO 1 New Message + Enable + 4 + 1 + + + RF1WE + Rx FIFO 1 Watermark Reached + Enable + 5 + 1 + + + RF1FE + Rx FIFO 1 Watermark Reached + Enable + 6 + 1 + + + RF1LE + Rx FIFO 1 Message Lost + Enable + 7 + 1 + + + HPME + High Priority Message + Enable + 8 + 1 + + + TCE + Transmission Completed + Enable + 9 + 1 + + + TCFE + Transmission Cancellation Finished + Enable + 10 + 1 + + + TEFE + Tx FIFO Empty Enable + 11 + 1 + + + TEFNE + Tx Event FIFO New Entry + Enable + 12 + 1 + + + TEFWE + Tx Event FIFO Watermark Reached + Enable + 13 + 1 + + + TEFFE + Tx Event FIFO Full Enable + 14 + 1 + + + TEFLE + Tx Event FIFO Element Lost + Enable + 15 + 1 + + + TSWE + Timestamp Wraparound + Enable + 16 + 1 + + + MRAFE + Message RAM Access Failure + Enable + 17 + 1 + + + TOOE + Timeout Occurred Enable + 18 + 1 + + + DRXE + Message stored to Dedicated Rx Buffer + Enable + 19 + 1 + + + BECE + Bit Error Corrected Interrupt + Enable + 20 + 1 + + + BEUE + Bit Error Uncorrected Interrupt + Enable + 21 + 1 + + + ELOE + Error Logging Overflow + Enable + 22 + 1 + + + EPE + Error Passive Enable + 23 + 1 + + + EWE + Warning Status Enable + 24 + 1 + + + BOE + Bus_Off Status Enable + 25 + 1 + + + WDIE + Watchdog Interrupt Enable + 26 + 1 + + + PEAE + Protocol Error in Arbitration Phase + Enable + 27 + 1 + + + PEDE + Protocol Error in Data Phase + Enable + 28 + 1 + + + ARAE + Access to Reserved Address + Enable + 29 + 1 + + + + + FDCAN_ILS + FDCAN_ILS + FDCAN Interrupt Line Select + Register + 0x58 + 0x20 + read-only + 0x00000000 + + + RF0NL + Rx FIFO 0 New Message Interrupt + Line + 0 + 1 + + + RF0WL + Rx FIFO 0 Watermark Reached Interrupt + Line + 1 + 1 + + + RF0FL + Rx FIFO 0 Full Interrupt + Line + 2 + 1 + + + RF0LL + Rx FIFO 0 Message Lost Interrupt + Line + 3 + 1 + + + RF1NL + Rx FIFO 1 New Message Interrupt + Line + 4 + 1 + + + RF1WL + Rx FIFO 1 Watermark Reached Interrupt + Line + 5 + 1 + + + RF1FL + Rx FIFO 1 Full Interrupt + Line + 6 + 1 + + + RF1LL + Rx FIFO 1 Message Lost Interrupt + Line + 7 + 1 + + + HPML + High Priority Message Interrupt + Line + 8 + 1 + + + TCL + Transmission Completed Interrupt + Line + 9 + 1 + + + TCFL + Transmission Cancellation Finished + Interrupt Line + 10 + 1 + + + TEFL + Tx FIFO Empty Interrupt + Line + 11 + 1 + + + TEFNL + Tx Event FIFO New Entry Interrupt + Line + 12 + 1 + + + TEFWL + Tx Event FIFO Watermark Reached + Interrupt Line + 13 + 1 + + + TEFFL + Tx Event FIFO Full Interrupt + Line + 14 + 1 + + + TEFLL + Tx Event FIFO Element Lost Interrupt + Line + 15 + 1 + + + TSWL + Timestamp Wraparound Interrupt + Line + 16 + 1 + + + MRAFL + Message RAM Access Failure Interrupt + Line + 17 + 1 + + + TOOL + Timeout Occurred Interrupt + Line + 18 + 1 + + + DRXL + Message stored to Dedicated Rx Buffer + Interrupt Line + 19 + 1 + + + BECL + Bit Error Corrected Interrupt + Line + 20 + 1 + + + BEUL + Bit Error Uncorrected Interrupt + Line + 21 + 1 + + + ELOL + Error Logging Overflow Interrupt + Line + 22 + 1 + + + EPL + Error Passive Interrupt + Line + 23 + 1 + + + EWL + Warning Status Interrupt + Line + 24 + 1 + + + BOL + Bus_Off Status + 25 + 1 + + + WDIL + Watchdog Interrupt Line + 26 + 1 + + + PEAL + Protocol Error in Arbitration Phase + Line + 27 + 1 + + + PEDL + Protocol Error in Data Phase + Line + 28 + 1 + + + ARAL + Access to Reserved Address + Line + 29 + 1 + + + + + FDCAN_ILE + FDCAN_ILE + FDCAN Interrupt Line Enable + Register + 0x5C + 0x20 + read-write + 0x00000000 + + + EINT0 + Enable Interrupt Line 0 + 0 + 1 + + + EINT1 + Enable Interrupt Line 1 + 1 + 1 + + + + + FDCAN_GFC + FDCAN_GFC + FDCAN Global Filter Configuration + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + RRFE + Reject Remote Frames + Extended + 0 + 1 + + + RRFS + Reject Remote Frames + Standard + 1 + 1 + + + ANFE + Accept Non-matching Frames + Extended + 2 + 2 + + + ANFS + Accept Non-matching Frames + Standard + 4 + 2 + + + + + FDCAN_SIDFC + FDCAN_SIDFC + FDCAN Standard ID Filter Configuration + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + FLSSA + Filter List Standard Start + Address + 2 + 14 + + + LSS + List Size Standard + 16 + 8 + + + + + FDCAN_XIDFC + FDCAN_XIDFC + FDCAN Extended ID Filter Configuration + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + FLESA + Filter List Standard Start + Address + 2 + 14 + + + LSE + List Size Extended + 16 + 8 + + + + + FDCAN_XIDAM + FDCAN_XIDAM + FDCAN Extended ID and Mask + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + EIDM + Extended ID Mask + 0 + 29 + + + + + FDCAN_HPMS + FDCAN_HPMS + FDCAN High Priority Message Status + Register + 0x94 + 0x20 + read-only + 0x00000000 + + + BIDX + Buffer Index + 0 + 6 + + + MSI + Message Storage Indicator + 6 + 2 + + + FIDX + Filter Index + 8 + 7 + + + FLST + Filter List + 15 + 1 + + + + + FDCAN_NDAT1 + FDCAN_NDAT1 + FDCAN New Data 1 Register + 0x98 + 0x20 + read-only + 0x00000000 + + + ND0 + New data + 0 + 1 + + + ND1 + New data + 1 + 1 + + + ND2 + New data + 2 + 1 + + + ND3 + New data + 3 + 1 + + + ND4 + New data + 4 + 1 + + + ND5 + New data + 5 + 1 + + + ND6 + New data + 6 + 1 + + + ND7 + New data + 7 + 1 + + + ND8 + New data + 8 + 1 + + + ND9 + New data + 9 + 1 + + + ND10 + New data + 10 + 1 + + + ND11 + New data + 11 + 1 + + + ND12 + New data + 12 + 1 + + + ND13 + New data + 13 + 1 + + + ND14 + New data + 14 + 1 + + + ND15 + New data + 15 + 1 + + + ND16 + New data + 16 + 1 + + + ND17 + New data + 17 + 1 + + + ND18 + New data + 18 + 1 + + + ND19 + New data + 19 + 1 + + + ND20 + New data + 20 + 1 + + + ND21 + New data + 21 + 1 + + + ND22 + New data + 22 + 1 + + + ND23 + New data + 23 + 1 + + + ND24 + New data + 24 + 1 + + + ND25 + New data + 25 + 1 + + + ND26 + New data + 26 + 1 + + + ND27 + New data + 27 + 1 + + + ND28 + New data + 28 + 1 + + + ND29 + New data + 29 + 1 + + + ND30 + New data + 30 + 1 + + + ND31 + New data + 31 + 1 + + + + + FDCAN_NDAT2 + FDCAN_NDAT2 + FDCAN New Data 2 Register + 0x9C + 0x20 + read-only + 0x00000000 + + + ND32 + New data + 0 + 1 + + + ND33 + New data + 1 + 1 + + + ND34 + New data + 2 + 1 + + + ND35 + New data + 3 + 1 + + + ND36 + New data + 4 + 1 + + + ND37 + New data + 5 + 1 + + + ND38 + New data + 6 + 1 + + + ND39 + New data + 7 + 1 + + + ND40 + New data + 8 + 1 + + + ND41 + New data + 9 + 1 + + + ND42 + New data + 10 + 1 + + + ND43 + New data + 11 + 1 + + + ND44 + New data + 12 + 1 + + + ND45 + New data + 13 + 1 + + + ND46 + New data + 14 + 1 + + + ND47 + New data + 15 + 1 + + + ND48 + New data + 16 + 1 + + + ND49 + New data + 17 + 1 + + + ND50 + New data + 18 + 1 + + + ND51 + New data + 19 + 1 + + + ND52 + New data + 20 + 1 + + + ND53 + New data + 21 + 1 + + + ND54 + New data + 22 + 1 + + + ND55 + New data + 23 + 1 + + + ND56 + New data + 24 + 1 + + + ND57 + New data + 25 + 1 + + + ND58 + New data + 26 + 1 + + + ND59 + New data + 27 + 1 + + + ND60 + New data + 28 + 1 + + + ND61 + New data + 29 + 1 + + + ND62 + New data + 30 + 1 + + + ND63 + New data + 31 + 1 + + + + + FDCAN_RXF0C + FDCAN_RXF0C + FDCAN Rx FIFO 0 Configuration + Register + 0xA0 + 0x20 + read-write + 0x00000000 + + + F0SA + Rx FIFO 0 Start Address + 2 + 14 + + + F0S + Rx FIFO 0 Size + 16 + 8 + + + F0WM + FIFO 0 Watermark + 24 + 8 + + + + + FDCAN_RXF0S + FDCAN_RXF0S + FDCAN Rx FIFO 0 Status + Register + 0xA4 + 0x20 + read-write + 0x00000000 + + + F0FL + Rx FIFO 0 Fill Level + 0 + 7 + + + F0G + Rx FIFO 0 Get Index + 8 + 6 + + + F0P + Rx FIFO 0 Put Index + 16 + 6 + + + F0F + Rx FIFO 0 Full + 24 + 1 + + + RF0L + Rx FIFO 0 Message Lost + 25 + 1 + + + + + FDCAN_RXF0A + FDCAN_RXF0A + CAN Rx FIFO 0 Acknowledge + Register + 0xA8 + 0x20 + read-write + 0x00000000 + + + FA01 + Rx FIFO 0 Acknowledge + Index + 0 + 6 + + + + + FDCAN_RXBC + FDCAN_RXBC + FDCAN Rx Buffer Configuration + Register + 0xAC + 0x20 + read-write + 0x00000000 + + + RBSA + Rx Buffer Start Address + 2 + 14 + + + + + FDCAN_RXF1C + FDCAN_RXF1C + FDCAN Rx FIFO 1 Configuration + Register + 0xB0 + 0x20 + read-write + 0x00000000 + + + F1SA + Rx FIFO 1 Start Address + 2 + 14 + + + F1S + Rx FIFO 1 Size + 16 + 7 + + + F1WM + Rx FIFO 1 Watermark + 24 + 7 + + + + + FDCAN_RXF1S + FDCAN_RXF1S + FDCAN Rx FIFO 1 Status + Register + 0xB4 + 0x20 + read-write + 0x00000000 + + + F1FL + Rx FIFO 1 Fill Level + 0 + 7 + + + F1GI + Rx FIFO 1 Get Index + 8 + 7 + + + F1PI + Rx FIFO 1 Put Index + 16 + 7 + + + F1F + Rx FIFO 1 Full + 24 + 1 + + + RF1L + Rx FIFO 1 Message Lost + 25 + 1 + + + DMS + Debug Message Status + 30 + 2 + + + + + FDCAN_RXF1A + FDCAN_RXF1A + FDCAN Rx FIFO 1 Acknowledge + Register + 0xB8 + 0x20 + read-write + 0x00000000 + + + F1AI + Rx FIFO 1 Acknowledge + Index + 0 + 6 + + + + + FDCAN_RXESC + FDCAN_RXESC + FDCAN Rx Buffer Element Size Configuration + Register + 0xBC + 0x20 + read-write + 0x00000000 + + + F0DS + Rx FIFO 1 Data Field Size: + 0 + 3 + + + F1DS + Rx FIFO 0 Data Field Size: + 4 + 3 + + + RBDS + Rx Buffer Data Field Size: + 8 + 3 + + + + + FDCAN_TXBC + FDCAN_TXBC + FDCAN Tx Buffer Configuration + Register + 0xC0 + 0x20 + read-write + 0x00000000 + + + TBSA + Tx Buffers Start Address + 2 + 14 + + + NDTB + Number of Dedicated Transmit + Buffers + 16 + 6 + + + TFQS + Transmit FIFO/Queue Size + 24 + 6 + + + TFQM + Tx FIFO/Queue Mode + 30 + 1 + + + + + FDCAN_TXFQS + FDCAN_TXFQS + FDCAN Tx FIFO/Queue Status + Register + 0xC4 + 0x20 + read-only + 0x00000000 + + + TFFL + Tx FIFO Free Level + 0 + 6 + + + TFGI + TFGI + 8 + 5 + + + TFQPI + Tx FIFO/Queue Put Index + 16 + 5 + + + TFQF + Tx FIFO/Queue Full + 21 + 1 + + + + + FDCAN_TXESC + FDCAN_TXESC + FDCAN Tx Buffer Element Size Configuration + Register + 0xC8 + 0x20 + read-write + 0x00000000 + + + TBDS + Tx Buffer Data Field Size: + 0 + 3 + + + + + FDCAN_TXBRP + FDCAN_TXBRP + FDCAN Tx Buffer Request Pending + Register + 0xCC + 0x20 + read-only + 0x00000000 + + + TRP + Transmission Request + Pending + 0 + 32 + + + + + FDCAN_TXBAR + FDCAN_TXBAR + FDCAN Tx Buffer Add Request + Register + 0xD0 + 0x20 + read-write + 0x00000000 + + + AR + Add Request + 0 + 32 + + + + + FDCAN_TXBCR + FDCAN_TXBCR + FDCAN Tx Buffer Cancellation Request + Register + 0xD4 + 0x20 + read-write + 0x00000000 + + + CR + Cancellation Request + 0 + 32 + + + + + FDCAN_TXBTO + FDCAN_TXBTO + FDCAN Tx Buffer Transmission Occurred + Register + 0xD8 + 0x20 + read-write + 0x00000000 + + + TO + Transmission Occurred. + 0 + 32 + + + + + FDCAN_TXBCF + FDCAN_TXBCF + FDCAN Tx Buffer Cancellation Finished + Register + 0xDC + 0x20 + read-only + 0x00000000 + + + CF + Cancellation Finished + 0 + 32 + + + + + FDCAN_TXBTIE + FDCAN_TXBTIE + FDCAN Tx Buffer Transmission Interrupt + Enable Register + 0xE0 + 0x20 + read-write + 0x00000000 + + + TIE + Transmission Interrupt + Enable + 0 + 32 + + + + + FDCAN_TXBCIE + FDCAN_TXBCIE + FDCAN Tx Buffer Cancellation Finished + Interrupt Enable Register + 0xE4 + 0x20 + read-write + 0x00000000 + + + CF + Cancellation Finished Interrupt + Enable + 0 + 32 + + + + + FDCAN_TXEFC + FDCAN_TXEFC + FDCAN Tx Event FIFO Configuration + Register + 0xF0 + 0x20 + read-write + 0x00000000 + + + EFSA + Event FIFO Start Address + 2 + 14 + + + EFS + Event FIFO Size + 16 + 6 + + + EFWM + Event FIFO Watermark + 24 + 6 + + + + + FDCAN_TXEFS + FDCAN_TXEFS + FDCAN Tx Event FIFO Status + Register + 0xF4 + 0x20 + read-write + 0x00000000 + + + EFFL + Event FIFO Fill Level + 0 + 6 + + + EFGI + Event FIFO Get Index. + 8 + 5 + + + EFF + Event FIFO Full. + 24 + 1 + + + TEFL + Tx Event FIFO Element + Lost. + 25 + 1 + + + + + FDCAN_TXEFA + FDCAN_TXEFA + FDCAN Tx Event FIFO Acknowledge + Register + 0xF8 + 0x20 + read-write + 0x00000000 + + + EFAI + Event FIFO Acknowledge + Index + 0 + 5 + + + + + FDCAN_TTTMC + FDCAN_TTTMC + FDCAN TT Trigger Memory Configuration + Register + 0x100 + 0x20 + read-write + 0x00000000 + + + TMSA + Trigger Memory Start + Address + 2 + 14 + + + TME + Trigger Memory Elements + 16 + 7 + + + + + FDCAN_TTRMC + FDCAN_TTRMC + FDCAN TT Reference Message Configuration + Register + 0x104 + 0x20 + read-write + 0x00000000 + + + RID + Reference Identifier. + 0 + 29 + + + XTD + Extended Identifier + 30 + 1 + + + RMPS + Reference Message Payload + Select + 31 + 1 + + + + + FDCAN_TTOCF + FDCAN_TTOCF + FDCAN TT Operation Configuration + Register + 0x108 + 0x20 + read-write + 0x00000000 + + + OM + Operation Mode + 0 + 2 + + + GEN + Gap Enable + 3 + 1 + + + TM + Time Master + 4 + 1 + + + LDSDL + LD of Synchronization Deviation + Limit + 5 + 3 + + + IRTO + Initial Reference Trigger + Offset + 8 + 7 + + + EECS + Enable External Clock + Synchronization + 15 + 1 + + + AWL + Application Watchdog Limit + 16 + 8 + + + EGTF + Enable Global Time + Filtering + 24 + 1 + + + ECC + Enable Clock Calibration + 25 + 1 + + + EVTP + Event Trigger Polarity + 26 + 1 + + + + + FDCAN_TTMLM + FDCAN_TTMLM + FDCAN TT Matrix Limits + Register + 0x10C + 0x20 + read-write + 0x00000000 + + + CCM + Cycle Count Max + 0 + 6 + + + CSS + Cycle Start + Synchronization + 6 + 2 + + + TXEW + Tx Enable Window + 8 + 4 + + + ENTT + Expected Number of Tx + Triggers + 16 + 12 + + + + + FDCAN_TURCF + FDCAN_TURCF + FDCAN TUR Configuration + Register + 0x110 + 0x20 + read-write + 0x00000000 + + + NCL + Numerator Configuration + Low. + 0 + 16 + + + DC + Denominator Configuration. + 16 + 14 + + + ELT + Enable Local Time + 31 + 1 + + + + + FDCAN_TTOCN + FDCAN_TTOCN + FDCAN TT Operation Control + Register + 0x114 + 0x20 + read-write + 0x00000000 + + + SGT + Set Global time + 0 + 1 + + + ECS + External Clock + Synchronization + 1 + 1 + + + SWP + Stop Watch Polarity + 2 + 1 + + + SWS + Stop Watch Source. + 3 + 2 + + + RTIE + Register Time Mark Interrupt Pulse + Enable + 5 + 1 + + + TMC + Register Time Mark Compare + 6 + 2 + + + TTIE + Trigger Time Mark Interrupt Pulse + Enable + 8 + 1 + + + GCS + Gap Control Select + 9 + 1 + + + FGP + Finish Gap. + 10 + 1 + + + TMG + Time Mark Gap + 11 + 1 + + + NIG + Next is Gap + 12 + 1 + + + ESCN + External Synchronization + Control + 13 + 1 + + + LCKC + TT Operation Control Register + Locked + 15 + 1 + + + + + CAN_TTGTP + CAN_TTGTP + FDCAN TT Global Time Preset + Register + 0x118 + 0x20 + read-write + 0x00000000 + + + NCL + Time Preset + 0 + 16 + + + CTP + Cycle Time Target Phase + 16 + 16 + + + + + FDCAN_TTTMK + FDCAN_TTTMK + FDCAN TT Time Mark Register + 0x11C + 0x20 + read-write + 0x00000000 + + + TM + Time Mark + 0 + 16 + + + TICC + Time Mark Cycle Code + 16 + 7 + + + LCKM + TT Time Mark Register + Locked + 31 + 1 + + + + + FDCAN_TTIR + FDCAN_TTIR + FDCAN TT Interrupt Register + 0x120 + 0x20 + read-write + 0x00000000 + + + SBC + Start of Basic Cycle + 0 + 1 + + + SMC + Start of Matrix Cycle + 1 + 1 + + + CSM + Change of Synchronization + Mode + 2 + 1 + + + SOG + Start of Gap + 3 + 1 + + + RTMI + Register Time Mark + Interrupt. + 4 + 1 + + + TTMI + Trigger Time Mark Event + Internal + 5 + 1 + + + SWE + Stop Watch Event + 6 + 1 + + + GTW + Global Time Wrap + 7 + 1 + + + GTD + Global Time Discontinuity + 8 + 1 + + + GTE + Global Time Error + 9 + 1 + + + TXU + Tx Count Underflow + 10 + 1 + + + TXO + Tx Count Overflow + 11 + 1 + + + SE1 + Scheduling Error 1 + 12 + 1 + + + SE2 + Scheduling Error 2 + 13 + 1 + + + ELC + Error Level Changed. + 14 + 1 + + + IWTG + Initialization Watch + Trigger + 15 + 1 + + + WT + Watch Trigger + 16 + 1 + + + AW + Application Watchdog + 17 + 1 + + + CER + Configuration Error + 18 + 1 + + + + + FDCAN_TTIE + FDCAN_TTIE + FDCAN TT Interrupt Enable + Register + 0x124 + 0x20 + read-write + 0x00000000 + + + SBCE + Start of Basic Cycle Interrupt + Enable + 0 + 1 + + + SMCE + Start of Matrix Cycle Interrupt + Enable + 1 + 1 + + + CSME + Change of Synchronization Mode Interrupt + Enable + 2 + 1 + + + SOGE + Start of Gap Interrupt + Enable + 3 + 1 + + + RTMIE + Register Time Mark Interrupt + Enable + 4 + 1 + + + TTMIE + Trigger Time Mark Event Internal + Interrupt Enable + 5 + 1 + + + SWEE + Stop Watch Event Interrupt + Enable + 6 + 1 + + + GTWE + Global Time Wrap Interrupt + Enable + 7 + 1 + + + GTDE + Global Time Discontinuity Interrupt + Enable + 8 + 1 + + + GTEE + Global Time Error Interrupt + Enable + 9 + 1 + + + TXUE + Tx Count Underflow Interrupt + Enable + 10 + 1 + + + TXOE + Tx Count Overflow Interrupt + Enable + 11 + 1 + + + SE1E + Scheduling Error 1 Interrupt + Enable + 12 + 1 + + + SE2E + Scheduling Error 2 Interrupt + Enable + 13 + 1 + + + ELCE + Change Error Level Interrupt + Enable + 14 + 1 + + + IWTGE + Initialization Watch Trigger Interrupt + Enable + 15 + 1 + + + WTE + Watch Trigger Interrupt + Enable + 16 + 1 + + + AWE + Application Watchdog Interrupt + Enable + 17 + 1 + + + CERE + Configuration Error Interrupt + Enable + 18 + 1 + + + + + FDCAN_TTILS + FDCAN_TTILS + FDCAN TT Interrupt Line Select + Register + 0x128 + 0x20 + read-write + 0x00000000 + + + SBCL + Start of Basic Cycle Interrupt + Line + 0 + 1 + + + SMCL + Start of Matrix Cycle Interrupt + Line + 1 + 1 + + + CSML + Change of Synchronization Mode Interrupt + Line + 2 + 1 + + + SOGL + Start of Gap Interrupt + Line + 3 + 1 + + + RTMIL + Register Time Mark Interrupt + Line + 4 + 1 + + + TTMIL + Trigger Time Mark Event Internal + Interrupt Line + 5 + 1 + + + SWEL + Stop Watch Event Interrupt + Line + 6 + 1 + + + GTWL + Global Time Wrap Interrupt + Line + 7 + 1 + + + GTDL + Global Time Discontinuity Interrupt + Line + 8 + 1 + + + GTEL + Global Time Error Interrupt + Line + 9 + 1 + + + TXUL + Tx Count Underflow Interrupt + Line + 10 + 1 + + + TXOL + Tx Count Overflow Interrupt + Line + 11 + 1 + + + SE1L + Scheduling Error 1 Interrupt + Line + 12 + 1 + + + SE2L + Scheduling Error 2 Interrupt + Line + 13 + 1 + + + ELCL + Change Error Level Interrupt + Line + 14 + 1 + + + IWTGL + Initialization Watch Trigger Interrupt + Line + 15 + 1 + + + WTL + Watch Trigger Interrupt + Line + 16 + 1 + + + AWL + Application Watchdog Interrupt + Line + 17 + 1 + + + CERL + Configuration Error Interrupt + Line + 18 + 1 + + + + + FDCAN_TTOST + FDCAN_TTOST + FDCAN TT Operation Status + Register + 0x12C + 0x20 + read-write + 0x00000000 + + + EL + Error Level + 0 + 2 + + + MS + Master State. + 2 + 2 + + + SYS + Synchronization State + 4 + 2 + + + GTP + Quality of Global Time + Phase + 6 + 1 + + + QCS + Quality of Clock Speed + 7 + 1 + + + RTO + Reference Trigger Offset + 8 + 8 + + + WGTD + Wait for Global Time + Discontinuity + 22 + 1 + + + GFI + Gap Finished Indicator. + 23 + 1 + + + TMP + Time Master Priority + 24 + 3 + + + GSI + Gap Started Indicator. + 27 + 1 + + + WFE + Wait for Event + 28 + 1 + + + AWE + Application Watchdog Event + 29 + 1 + + + WECS + Wait for External Clock + Synchronization + 30 + 1 + + + SPL + Schedule Phase Lock + 31 + 1 + + + + + FDCAN_TURNA + FDCAN_TURNA + FDCAN TUR Numerator Actual + Register + 0x130 + 0x20 + read-only + 0x00000000 + + + NAV + Numerator Actual Value + 0 + 18 + + + + + FDCAN_TTLGT + FDCAN_TTLGT + FDCAN TT Local and Global Time + Register + 0x134 + 0x20 + read-only + 0x00000000 + + + LT + Local Time + 0 + 16 + + + GT + Global Time + 16 + 16 + + + + + FDCAN_TTCTC + FDCAN_TTCTC + FDCAN TT Cycle Time and Count + Register + 0x138 + 0x20 + read-only + 0x00000000 + + + CT + Cycle Time + 0 + 16 + + + CC + Cycle Count + 16 + 6 + + + + + FDCAN_TTCPT + FDCAN_TTCPT + FDCAN TT Capture Time Register + 0x13C + 0x20 + read-only + 0x00000000 + + + CT + Cycle Count Value + 0 + 6 + + + SWV + Stop Watch Value + 16 + 16 + + + + + FDCAN_TTCSM + FDCAN_TTCSM + FDCAN TT Cycle Sync Mark + Register + 0x140 + 0x20 + read-only + 0x00000000 + + + CSM + Cycle Sync Mark + 0 + 16 + + + + + FDCAN_TTTS + FDCAN_TTTS + FDCAN TT Trigger Select + Register + 0x300 + 0x20 + read-write + 0x00000000 + + + SWTDEL + Stop watch trigger input + selection + 0 + 2 + + + EVTSEL + Event trigger input + selection + 4 + 2 + + + + + + + FDCAN2 + 0x4000A400 + + FDCAN2_IT0 + FDCAN2 Interrupt 0 + 20 + + + FDCAN2_IT1 + FDCAN2 Interrupt 1 + 22 + + + + CAN_CCU + CCU registers + FDCAN + 0x4000A800 + + 0x0 + 0x400 + registers + + + + CREL + CREL + Clock Calibration Unit Core Release + Register + 0x0 + 0x20 + read-write + 0x00000000 + + + DAY + Time Stamp Day + 0 + 8 + + + MON + Time Stamp Month + 8 + 8 + + + YEAR + Time Stamp Year + 16 + 4 + + + SUBSTEP + Sub-step of Core Release + 20 + 4 + + + STEP + Step of Core Release + 24 + 4 + + + REL + Core Release + 28 + 4 + + + + + CCFG + CCFG + Calibration Configuration + Register + 0x4 + 0x20 + read-write + 0x00000000 + + + TQBT + Time Quanta per Bit Time + 0 + 5 + + + BCC + Bypass Clock Calibration + 6 + 1 + + + CFL + Calibration Field Length + 7 + 1 + + + OCPM + Oscillator Clock Periods + Minimum + 8 + 8 + + + CDIV + Clock Divider + 16 + 4 + + + SWR + Software Reset + 31 + 1 + + + + + CSTAT + CSTAT + Calibration Status Register + 0x8 + 0x20 + read-write + 0x00000000 + + + OCPC + Oscillator Clock Period + Counter + 0 + 18 + + + TQC + Time Quanta Counter + 18 + 11 + + + CALS + Calibration State + 30 + 2 + + + + + CWD + CWD + Calibration Watchdog Register + 0xC + 0x20 + read-write + 0x00000000 + + + WDC + WDC + 0 + 16 + + + WDV + WDV + 16 + 16 + + + + + IR + IR + Clock Calibration Unit Interrupt + Register + 0x10 + 0x20 + read-write + 0x00000000 + + + CWE + Calibration Watchdog Event + 0 + 1 + + + CSC + Calibration State Changed + 1 + 1 + + + + + IE + IE + Clock Calibration Unit Interrupt Enable + Register + 0x14 + 0x20 + read-write + 0x00000000 + + + CWEE + Calibration Watchdog Event + Enable + 0 + 1 + + + CSCE + Calibration State Changed + Enable + 1 + 1 + + + + + + + MDIOS + Management data input/output slave + MDIOS + 0x40009400 + + 0x0 + 0x400 + registers + + + MDIOS_WKUP + MDIOS wakeup + 119 + + + MDIOS + MDIOS global interrupt + 120 + + + + CR + CR + MDIOS configuration register + 0x0 + 0x20 + read-write + 0x00000000 + + + EN + Peripheral enable + 0 + 1 + + + WRIE + Register write interrupt + enable + 1 + 1 + + + RDIE + Register Read Interrupt + Enable + 2 + 1 + + + EIE + Error interrupt enable + 3 + 1 + + + DPC + Disable Preamble Check + 7 + 1 + + + PORT_ADDRESS + Slaves's address + 8 + 5 + + + + + WRFR + WRFR + MDIOS write flag register + 0x4 + 0x20 + read-only + 0x00000000 + + + WRF + Write flags for MDIO registers 0 to + 31 + 0 + 32 + + + + + CWRFR + CWRFR + MDIOS clear write flag + register + 0x8 + 0x20 + read-write + 0x00000000 + + + CWRF + Clear the write flag + 0 + 32 + + + + + RDFR + RDFR + MDIOS read flag register + 0xC + 0x20 + read-only + 0x00000000 + + + RDF + Read flags for MDIO registers 0 to + 31 + 0 + 32 + + + + + CRDFR + CRDFR + MDIOS clear read flag register + 0x10 + 0x20 + read-write + 0x00000000 + + + CRDF + Clear the read flag + 0 + 32 + + + + + SR + SR + MDIOS status register + 0x14 + 0x20 + read-only + 0x00000000 + + + PERF + Preamble error flag + 0 + 1 + + + SERF + Start error flag + 1 + 1 + + + TERF + Turnaround error flag + 2 + 1 + + + + + CLRFR + CLRFR + MDIOS clear flag register + 0x18 + 0x20 + read-write + 0x00000000 + + + CPERF + Clear the preamble error + flag + 0 + 1 + + + CSERF + Clear the start error flag + 1 + 1 + + + CTERF + Clear the turnaround error + flag + 2 + 1 + + + + + DINR0 + DINR0 + MDIOS input data register 0 + 0x1C + 0x20 + read-only + 0x00000000 + + + DIN0 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR1 + DINR1 + MDIOS input data register 1 + 0x20 + 0x20 + read-only + 0x00000000 + + + DIN1 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR2 + DINR2 + MDIOS input data register 2 + 0x24 + 0x20 + read-only + 0x00000000 + + + DIN2 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR3 + DINR3 + MDIOS input data register 3 + 0x28 + 0x20 + read-only + 0x00000000 + + + DIN3 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR4 + DINR4 + MDIOS input data register 4 + 0x2C + 0x20 + read-only + 0x00000000 + + + DIN4 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR5 + DINR5 + MDIOS input data register 5 + 0x30 + 0x20 + read-only + 0x00000000 + + + DIN5 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR6 + DINR6 + MDIOS input data register 6 + 0x34 + 0x20 + read-only + 0x00000000 + + + DIN6 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR7 + DINR7 + MDIOS input data register 7 + 0x38 + 0x20 + read-only + 0x00000000 + + + DIN7 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR8 + DINR8 + MDIOS input data register 8 + 0x3C + 0x20 + read-only + 0x00000000 + + + DIN8 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR9 + DINR9 + MDIOS input data register 9 + 0x40 + 0x20 + read-only + 0x00000000 + + + DIN9 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR10 + DINR10 + MDIOS input data register 10 + 0x44 + 0x20 + read-only + 0x00000000 + + + DIN10 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR11 + DINR11 + MDIOS input data register 11 + 0x48 + 0x20 + read-only + 0x00000000 + + + DIN11 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR12 + DINR12 + MDIOS input data register 12 + 0x4C + 0x20 + read-only + 0x00000000 + + + DIN12 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR13 + DINR13 + MDIOS input data register 13 + 0x50 + 0x20 + read-only + 0x00000000 + + + DIN13 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR14 + DINR14 + MDIOS input data register 14 + 0x54 + 0x20 + read-only + 0x00000000 + + + DIN14 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR15 + DINR15 + MDIOS input data register 15 + 0x58 + 0x20 + read-only + 0x00000000 + + + DIN15 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR16 + DINR16 + MDIOS input data register 16 + 0x5C + 0x20 + read-only + 0x00000000 + + + DIN16 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR17 + DINR17 + MDIOS input data register 17 + 0x60 + 0x20 + read-only + 0x00000000 + + + DIN17 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR18 + DINR18 + MDIOS input data register 18 + 0x64 + 0x20 + read-only + 0x00000000 + + + DIN18 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR19 + DINR19 + MDIOS input data register 19 + 0x68 + 0x20 + read-only + 0x00000000 + + + DIN19 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR20 + DINR20 + MDIOS input data register 20 + 0x6C + 0x20 + read-only + 0x00000000 + + + DIN20 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR21 + DINR21 + MDIOS input data register 21 + 0x70 + 0x20 + read-only + 0x00000000 + + + DIN21 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR22 + DINR22 + MDIOS input data register 22 + 0x74 + 0x20 + read-only + 0x00000000 + + + DIN22 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR23 + DINR23 + MDIOS input data register 23 + 0x78 + 0x20 + read-only + 0x00000000 + + + DIN23 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR24 + DINR24 + MDIOS input data register 24 + 0x7C + 0x20 + read-only + 0x00000000 + + + DIN24 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR25 + DINR25 + MDIOS input data register 25 + 0x80 + 0x20 + read-only + 0x00000000 + + + DIN25 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR26 + DINR26 + MDIOS input data register 26 + 0x84 + 0x20 + read-only + 0x00000000 + + + DIN26 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR27 + DINR27 + MDIOS input data register 27 + 0x88 + 0x20 + read-only + 0x00000000 + + + DIN27 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR28 + DINR28 + MDIOS input data register 28 + 0x8C + 0x20 + read-only + 0x00000000 + + + DIN28 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR29 + DINR29 + MDIOS input data register 29 + 0x90 + 0x20 + read-only + 0x00000000 + + + DIN29 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR30 + DINR30 + MDIOS input data register 30 + 0x94 + 0x20 + read-only + 0x00000000 + + + DIN30 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DINR31 + DINR31 + MDIOS input data register 31 + 0x98 + 0x20 + read-only + 0x00000000 + + + DIN31 + Input data received from MDIO Master + during write frames + 0 + 16 + + + + + DOUTR0 + DOUTR0 + MDIOS output data register 0 + 0x9C + 0x20 + read-write + 0x00000000 + + + DOUT0 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR1 + DOUTR1 + MDIOS output data register 1 + 0xA0 + 0x20 + read-write + 0x00000000 + + + DOUT1 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR2 + DOUTR2 + MDIOS output data register 2 + 0xA4 + 0x20 + read-write + 0x00000000 + + + DOUT2 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR3 + DOUTR3 + MDIOS output data register 3 + 0xA8 + 0x20 + read-write + 0x00000000 + + + DOUT3 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR4 + DOUTR4 + MDIOS output data register 4 + 0xAC + 0x20 + read-write + 0x00000000 + + + DOUT4 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR5 + DOUTR5 + MDIOS output data register 5 + 0xB0 + 0x20 + read-write + 0x00000000 + + + DOUT5 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR6 + DOUTR6 + MDIOS output data register 6 + 0xB4 + 0x20 + read-write + 0x00000000 + + + DOUT6 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR7 + DOUTR7 + MDIOS output data register 7 + 0xB8 + 0x20 + read-write + 0x00000000 + + + DOUT7 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR8 + DOUTR8 + MDIOS output data register 8 + 0xBC + 0x20 + read-write + 0x00000000 + + + DOUT8 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR9 + DOUTR9 + MDIOS output data register 9 + 0xC0 + 0x20 + read-write + 0x00000000 + + + DOUT9 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR10 + DOUTR10 + MDIOS output data register 10 + 0xC4 + 0x20 + read-write + 0x00000000 + + + DOUT10 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR11 + DOUTR11 + MDIOS output data register 11 + 0xC8 + 0x20 + read-write + 0x00000000 + + + DOUT11 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR12 + DOUTR12 + MDIOS output data register 12 + 0xCC + 0x20 + read-write + 0x00000000 + + + DOUT12 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR13 + DOUTR13 + MDIOS output data register 13 + 0xD0 + 0x20 + read-write + 0x00000000 + + + DOUT13 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR14 + DOUTR14 + MDIOS output data register 14 + 0xD4 + 0x20 + read-write + 0x00000000 + + + DOUT14 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR15 + DOUTR15 + MDIOS output data register 15 + 0xD8 + 0x20 + read-write + 0x00000000 + + + DOUT15 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR16 + DOUTR16 + MDIOS output data register 16 + 0xDC + 0x20 + read-write + 0x00000000 + + + DOUT16 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR17 + DOUTR17 + MDIOS output data register 17 + 0xE0 + 0x20 + read-write + 0x00000000 + + + DOUT17 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR18 + DOUTR18 + MDIOS output data register 18 + 0xE4 + 0x20 + read-write + 0x00000000 + + + DOUT18 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR19 + DOUTR19 + MDIOS output data register 19 + 0xE8 + 0x20 + read-write + 0x00000000 + + + DOUT19 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR20 + DOUTR20 + MDIOS output data register 20 + 0xEC + 0x20 + read-write + 0x00000000 + + + DOUT20 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR21 + DOUTR21 + MDIOS output data register 21 + 0xF0 + 0x20 + read-write + 0x00000000 + + + DOUT21 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR22 + DOUTR22 + MDIOS output data register 22 + 0xF4 + 0x20 + read-write + 0x00000000 + + + DOUT22 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR23 + DOUTR23 + MDIOS output data register 23 + 0xF8 + 0x20 + read-write + 0x00000000 + + + DOUT23 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR24 + DOUTR24 + MDIOS output data register 24 + 0xFC + 0x20 + read-write + 0x00000000 + + + DOUT24 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR25 + DOUTR25 + MDIOS output data register 25 + 0x100 + 0x20 + read-write + 0x00000000 + + + DOUT25 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR26 + DOUTR26 + MDIOS output data register 26 + 0x104 + 0x20 + read-write + 0x00000000 + + + DOUT26 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR27 + DOUTR27 + MDIOS output data register 27 + 0x108 + 0x20 + read-write + 0x00000000 + + + DOUT27 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR28 + DOUTR28 + MDIOS output data register 28 + 0x10C + 0x20 + read-write + 0x00000000 + + + DOUT28 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR29 + DOUTR29 + MDIOS output data register 29 + 0x110 + 0x20 + read-write + 0x00000000 + + + DOUT29 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR30 + DOUTR30 + MDIOS output data register 30 + 0x114 + 0x20 + read-write + 0x00000000 + + + DOUT30 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + DOUTR31 + DOUTR31 + MDIOS output data register 31 + 0x118 + 0x20 + read-write + 0x00000000 + + + DOUT31 + Output data sent to MDIO Master during + read frames + 0 + 16 + + + + + + + OPAMP + Operational amplifiers + OPAMP + 0x40009000 + + 0x0 + 0x400 + registers + + + + OPAMP1_CSR + OPAMP1_CSR + OPAMP1 control/status register + 0x0 + 0x20 + read-write + 0x00000000 + + + OPAEN + Operational amplifier + Enable + 0 + 1 + + + FORCE_VP + Force internal reference on VP (reserved + for test + 1 + 1 + + + VP_SEL + Operational amplifier PGA + mode + 2 + 2 + + + VM_SEL + Inverting input selection + 5 + 2 + + + OPAHSM + Operational amplifier high-speed + mode + 8 + 1 + + + CALON + Calibration mode enabled + 11 + 1 + + + CALSEL + Calibration selection + 12 + 2 + + + PGA_GAIN + allows to switch from AOP offset trimmed + values to AOP offset + 14 + 4 + + + USERTRIM + User trimming enable + 18 + 1 + + + TSTREF + OPAMP calibration reference voltage + output control (reserved for test) + 29 + 1 + + + CALOUT + Operational amplifier calibration + output + 30 + 1 + + + + + OPAMP1_OTR + OPAMP1_OTR + OPAMP1 offset trimming register in normal + mode + 0x4 + 0x20 + read-write + 0x00000000 + + + TRIMOFFSETN + Trim for NMOS differential + pairs + 0 + 5 + + + TRIMOFFSETP + Trim for PMOS differential + pairs + 8 + 5 + + + + + OPAMP1_HSOTR + OPAMP1_HSOTR + OPAMP1 offset trimming register in low-power + mode + 0x8 + 0x20 + read-write + 0x00000000 + + + TRIMLPOFFSETN + Trim for NMOS differential + pairs + 0 + 5 + + + TRIMLPOFFSETP + Trim for PMOS differential + pairs + 8 + 5 + + + + + OPAMP2_CSR + OPAMP2_CSR + OPAMP2 control/status register + 0x10 + 0x20 + read-write + 0x00000000 + + + OPAEN + Operational amplifier + Enable + 0 + 1 + + + FORCE_VP + Force internal reference on VP (reserved + for test) + 1 + 1 + + + VM_SEL + Inverting input selection + 5 + 2 + + + OPAHSM + Operational amplifier high-speed + mode + 8 + 1 + + + CALON + Calibration mode enabled + 11 + 1 + + + CALSEL + Calibration selection + 12 + 2 + + + PGA_GAIN + Operational amplifier Programmable + amplifier gain value + 14 + 4 + + + USERTRIM + User trimming enable + 18 + 1 + + + TSTREF + OPAMP calibration reference voltage + output control (reserved for test) + 29 + 1 + + + CALOUT + Operational amplifier calibration + output + 30 + 1 + + + + + OPAMP2_OTR + OPAMP2_OTR + OPAMP2 offset trimming register in normal + mode + 0x14 + 0x20 + read-write + 0x00000000 + + + TRIMOFFSETN + Trim for NMOS differential + pairs + 0 + 5 + + + TRIMOFFSETP + Trim for PMOS differential + pairs + 8 + 5 + + + + + OPAMP2_HSOTR + OPAMP2_HSOTR + OPAMP2 offset trimming register in low-power + mode + 0x18 + 0x20 + read-write + 0x00000000 + + + TRIMLPOFFSETN + Trim for NMOS differential + pairs + 0 + 5 + + + TRIMLPOFFSETP + Trim for PMOS differential + pairs + 8 + 5 + + + + + + + SWPMI + Single Wire Protocol Master + Interface + SWPMI + 0x40008800 + + 0x0 + 0x400 + registers + + + + CR + CR + SWPMI Configuration/Control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + RXDMA + Reception DMA enable + 0 + 1 + + + TXDMA + Transmission DMA enable + 1 + 1 + + + RXMODE + Reception buffering mode + 2 + 1 + + + TXMODE + Transmission buffering + mode + 3 + 1 + + + LPBK + Loopback mode enable + 4 + 1 + + + SWPACT + Single wire protocol master interface + activate + 5 + 1 + + + DEACT + Single wire protocol master interface + deactivate + 10 + 1 + + + SWPTEN + Single wire protocol master transceiver + enable + 11 + 1 + + + + + BRR + BRR + SWPMI Bitrate register + 0x4 + 0x20 + read-write + 0x00000001 + + + BR + Bitrate prescaler + 0 + 8 + + + + + ISR + ISR + SWPMI Interrupt and Status + register + 0xC + 0x20 + read-only + 0x000002C2 + + + RXBFF + Receive buffer full flag + 0 + 1 + + + TXBEF + Transmit buffer empty flag + 1 + 1 + + + RXBERF + Receive CRC error flag + 2 + 1 + + + RXOVRF + Receive overrun error flag + 3 + 1 + + + TXUNRF + Transmit underrun error + flag + 4 + 1 + + + RXNE + Receive data register not + empty + 5 + 1 + + + TXE + Transmit data register + empty + 6 + 1 + + + TCF + Transfer complete flag + 7 + 1 + + + SRF + Slave resume flag + 8 + 1 + + + SUSP + SUSPEND flag + 9 + 1 + + + DEACTF + DEACTIVATED flag + 10 + 1 + + + RDYF + transceiver ready flag + 11 + 1 + + + + + ICR + ICR + SWPMI Interrupt Flag Clear + register + 0x10 + 0x20 + write-only + 0x00000000 + + + CRXBFF + Clear receive buffer full + flag + 0 + 1 + + + CTXBEF + Clear transmit buffer empty + flag + 1 + 1 + + + CRXBERF + Clear receive CRC error + flag + 2 + 1 + + + CRXOVRF + Clear receive overrun error + flag + 3 + 1 + + + CTXUNRF + Clear transmit underrun error + flag + 4 + 1 + + + CTCF + Clear transfer complete + flag + 7 + 1 + + + CSRF + Clear slave resume flag + 8 + 1 + + + CRDYF + Clear transceiver ready + flag + 11 + 1 + + + + + IER + IER + SWPMI Interrupt Enable + register + 0x14 + 0x20 + read-write + 0x00000000 + + + RXBFIE + Receive buffer full interrupt + enable + 0 + 1 + + + TXBEIE + Transmit buffer empty interrupt + enable + 1 + 1 + + + RXBERIE + Receive CRC error interrupt + enable + 2 + 1 + + + RXOVRIE + Receive overrun error interrupt + enable + 3 + 1 + + + TXUNRIE + Transmit underrun error interrupt + enable + 4 + 1 + + + RIE + Receive interrupt enable + 5 + 1 + + + TIE + Transmit interrupt enable + 6 + 1 + + + TCIE + Transmit complete interrupt + enable + 7 + 1 + + + SRIE + Slave resume interrupt + enable + 8 + 1 + + + RDYIE + Transceiver ready interrupt + enable + 11 + 1 + + + + + RFL + RFL + SWPMI Receive Frame Length + register + 0x18 + 0x20 + read-only + 0x00000000 + + + RFL + Receive frame length + 0 + 5 + + + + + TDR + TDR + SWPMI Transmit data register + 0x1C + 0x20 + write-only + 0x00000000 + + + TD + Transmit data + 0 + 32 + + + + + RDR + RDR + SWPMI Receive data register + 0x20 + 0x20 + read-only + 0x00000000 + + + RD + received data + 0 + 32 + + + + + OR + OR + SWPMI Option register + 0x24 + 0x20 + read-write + 0x00000000 + + + SWP_TBYP + SWP transceiver bypass + 0 + 1 + + + SWP_CLASS + SWP class selection + 1 + 1 + + + + + + + TIM2 + General purpose timers + TIM + 0x40000000 + + 0x0 + 0x400 + registers + + + TIM2 + TIM2 global interrupt + 28 + + + SWPMI1 + SWPMI global interrupt + 115 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + CKD + Clock division + 8 + 2 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + CMS + Center-aligned mode + selection + 5 + 2 + + + DIR + Direction + 4 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + TI1S + TI1 selection + 7 + 1 + + + MMS + Master mode selection + 4 + 3 + + + CCDS + Capture/compare DMA + selection + 3 + 1 + + + + + SMCR + SMCR + slave mode control register + 0x8 + 0x20 + read-write + 0x0000 + + + TS_4_3 + Trigger selection + 20 + 2 + + + SMS_3 + Slave mode selection - bit + 3 + 16 + 1 + + + ETP + External trigger polarity + 15 + 1 + + + ECE + External clock enable + 14 + 1 + + + ETPS + External trigger prescaler + 12 + 2 + + + ETF + External trigger filter + 8 + 4 + + + MSM + Master/Slave mode + 7 + 1 + + + TS + Trigger selection + 4 + 3 + + + SMS + Slave mode selection + 0 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + TDE + Trigger DMA request enable + 14 + 1 + + + CC4DE + Capture/Compare 4 DMA request + enable + 12 + 1 + + + CC3DE + Capture/Compare 3 DMA request + enable + 11 + 1 + + + CC2DE + Capture/Compare 2 DMA request + enable + 10 + 1 + + + CC1DE + Capture/Compare 1 DMA request + enable + 9 + 1 + + + UDE + Update DMA request enable + 8 + 1 + + + TIE + Trigger interrupt enable + 6 + 1 + + + CC4IE + Capture/Compare 4 interrupt + enable + 4 + 1 + + + CC3IE + Capture/Compare 3 interrupt + enable + 3 + 1 + + + CC2IE + Capture/Compare 2 interrupt + enable + 2 + 1 + + + CC1IE + Capture/Compare 1 interrupt + enable + 1 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + CC4OF + Capture/Compare 4 overcapture + flag + 12 + 1 + + + CC3OF + Capture/Compare 3 overcapture + flag + 11 + 1 + + + CC2OF + Capture/compare 2 overcapture + flag + 10 + 1 + + + CC1OF + Capture/Compare 1 overcapture + flag + 9 + 1 + + + TIF + Trigger interrupt flag + 6 + 1 + + + CC4IF + Capture/Compare 4 interrupt + flag + 4 + 1 + + + CC3IF + Capture/Compare 3 interrupt + flag + 3 + 1 + + + CC2IF + Capture/Compare 2 interrupt + flag + 2 + 1 + + + CC1IF + Capture/compare 1 interrupt + flag + 1 + 1 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + TG + Trigger generation + 6 + 1 + + + CC4G + Capture/compare 4 + generation + 4 + 1 + + + CC3G + Capture/compare 3 + generation + 3 + 1 + + + CC2G + Capture/compare 2 + generation + 2 + 1 + + + CC1G + Capture/compare 1 + generation + 1 + 1 + + + UG + Update generation + 0 + 1 + + + + + CCMR1_Output + CCMR1_Output + capture/compare mode register 1 (output + mode) + 0x18 + 0x20 + read-write + 0x00000000 + + + CC1S + CC1S + 0 + 2 + + + OC1FE + OC1FE + 2 + 1 + + + OC1PE + OC1PE + 3 + 1 + + + OC1M + OC1M + 4 + 3 + + + OC1CE + OC1CE + 7 + 1 + + + CC2S + CC2S + 8 + 2 + + + OC2FE + OC2FE + 10 + 1 + + + OC2PE + OC2PE + 11 + 1 + + + OC2M + OC2M + 12 + 3 + + + OC2CE + OC2CE + 15 + 1 + + + OC1M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + OC2M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + + + CCMR1_Input + CCMR1_Input + capture/compare mode register 1 (input + mode) + CCMR1_Output + 0x18 + 0x20 + read-write + 0x00000000 + + + IC2F + Input capture 2 filter + 12 + 4 + + + IC2PCS + Input capture 2 prescaler + 10 + 2 + + + CC2S + Capture/Compare 2 + selection + 8 + 2 + + + IC1F + Input capture 1 filter + 4 + 4 + + + ICPCS + Input capture 1 prescaler + 2 + 2 + + + CC1S + Capture/Compare 1 + selection + 0 + 2 + + + + + CCMR2_Output + CCMR2_Output + capture/compare mode register 2 (output + mode) + 0x1C + 0x20 + read-write + 0x00000000 + + + OC4M_3 + Output Compare 2 mode - bit + 3 + 24 + 1 + + + OC3M_3 + Output Compare 1 mode - bit + 3 + 16 + 1 + + + O24CE + O24CE + 15 + 1 + + + OC4M + OC4M + 12 + 3 + + + OC4PE + OC4PE + 11 + 1 + + + OC4FE + OC4FE + 10 + 1 + + + CC4S + CC4S + 8 + 2 + + + OC3CE + OC3CE + 7 + 1 + + + OC3M + OC3M + 4 + 3 + + + OC3PE + OC3PE + 3 + 1 + + + OC3FE + OC3FE + 2 + 1 + + + CC3S + CC3S + 0 + 2 + + + + + CCMR2_Input + CCMR2_Input + capture/compare mode register 2 (input + mode) + CCMR2_Output + 0x1C + 0x20 + read-write + 0x00000000 + + + IC4F + Input capture 4 filter + 12 + 4 + + + IC4PSC + Input capture 4 prescaler + 10 + 2 + + + CC4S + Capture/Compare 4 + selection + 8 + 2 + + + IC3F + Input capture 3 filter + 4 + 4 + + + IC3PSC + Input capture 3 prescaler + 2 + 2 + + + CC3S + Capture/compare 3 + selection + 0 + 2 + + + + + CCER + CCER + capture/compare enable + register + 0x20 + 0x20 + read-write + 0x0000 + + + CC4NP + Capture/Compare 4 output + Polarity + 15 + 1 + + + CC4P + Capture/Compare 3 output + Polarity + 13 + 1 + + + CC4E + Capture/Compare 4 output + enable + 12 + 1 + + + CC3NP + Capture/Compare 3 output + Polarity + 11 + 1 + + + CC3P + Capture/Compare 3 output + Polarity + 9 + 1 + + + CC3E + Capture/Compare 3 output + enable + 8 + 1 + + + CC2NP + Capture/Compare 2 output + Polarity + 7 + 1 + + + CC2P + Capture/Compare 2 output + Polarity + 5 + 1 + + + CC2E + Capture/Compare 2 output + enable + 4 + 1 + + + CC1NP + Capture/Compare 1 output + Polarity + 3 + 1 + + + CC1P + Capture/Compare 1 output + Polarity + 1 + 1 + + + CC1E + Capture/Compare 1 output + enable + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT_L + low counter value + 0 + 16 + + + CNT_H + High counter value + 16 + 16 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR_H + High Auto-reload value + 16 + 16 + + + ARR_L + Low Auto-reload value + 0 + 16 + + + + + CCR1 + CCR1 + capture/compare register 1 + 0x34 + 0x20 + read-write + 0x00000000 + + + CCR1_H + High Capture/Compare 1 + value + 16 + 16 + + + CCR1_L + Low Capture/Compare 1 + value + 0 + 16 + + + + + CCR2 + CCR2 + capture/compare register 2 + 0x38 + 0x20 + read-write + 0x00000000 + + + CCR2_H + High Capture/Compare 2 + value + 16 + 16 + + + CCR2_L + Low Capture/Compare 2 + value + 0 + 16 + + + + + CCR3 + CCR3 + capture/compare register 3 + 0x3C + 0x20 + read-write + 0x00000000 + + + CCR3_H + High Capture/Compare value + 16 + 16 + + + CCR3_L + Low Capture/Compare value + 0 + 16 + + + + + CCR4 + CCR4 + capture/compare register 4 + 0x40 + 0x20 + read-write + 0x00000000 + + + CCR4_H + High Capture/Compare value + 16 + 16 + + + CCR4_L + Low Capture/Compare value + 0 + 16 + + + + + DCR + DCR + DMA control register + 0x48 + 0x20 + read-write + 0x0000 + + + DBL + DMA burst length + 8 + 5 + + + DBA + DMA base address + 0 + 5 + + + + + DMAR + DMAR + DMA address for full transfer + 0x4C + 0x20 + read-write + 0x0000 + + + DMAB + DMA register for burst + accesses + 0 + 16 + + + + + AF1 + AF1 + TIM alternate function option register + 1 + 0x60 + 0x20 + read-write + 0x0000 + + + ETRSEL + ETR source selection + 14 + 4 + + + + + TISEL + TISEL + TIM timer input selection + register + 0x68 + 0x20 + read-write + 0x0000 + + + TI1SEL + TI1[0] to TI1[15] input + selection + 0 + 4 + + + TI2SEL + TI2[0] to TI2[15] input + selection + 8 + 4 + + + TI3SEL + TI3[0] to TI3[15] input + selection + 16 + 4 + + + TI4SEL + TI4[0] to TI4[15] input + selection + 24 + 4 + + + + + + + TIM3 + 0x40000400 + + TIM3 + TIM3 global interrupt + 29 + + + + TIM4 + 0x40000800 + + + TIM5 + 0x40000C00 + + TIM4 + TIM4 global interrupt + 30 + + + TIM5 + TIM5 global interrupt + 50 + + + + TIM12 + 0x40001800 + + TIM8_BRK_TIM12 + TIM8 and 12 break global + 43 + + + + TIM13 + 0x40001C00 + + TIM8_UP_TIM13 + TIM8 and 13 update global + 44 + + + + TIM14 + 0x40002000 + + TIM8_TRG_COM_TIM14 + TIM8 and 14 trigger /commutation and + global + 45 + + + + TIM6 + Basic timers + TIM + 0x40001000 + + 0x0 + 0x400 + registers + + + TIM6_DAC + TIM6 global interrupt + 54 + + + + CR1 + CR1 + control register 1 + 0x0 + 0x20 + read-write + 0x0000 + + + UIFREMAP + UIF status bit remapping + 11 + 1 + + + ARPE + Auto-reload preload enable + 7 + 1 + + + OPM + One-pulse mode + 3 + 1 + + + URS + Update request source + 2 + 1 + + + UDIS + Update disable + 1 + 1 + + + CEN + Counter enable + 0 + 1 + + + + + CR2 + CR2 + control register 2 + 0x4 + 0x20 + read-write + 0x0000 + + + MMS + Master mode selection + 4 + 3 + + + + + DIER + DIER + DMA/Interrupt enable register + 0xC + 0x20 + read-write + 0x0000 + + + UDE + Update DMA request enable + 8 + 1 + + + UIE + Update interrupt enable + 0 + 1 + + + + + SR + SR + status register + 0x10 + 0x20 + read-write + 0x0000 + + + UIF + Update interrupt flag + 0 + 1 + + + + + EGR + EGR + event generation register + 0x14 + 0x20 + write-only + 0x0000 + + + UG + Update generation + 0 + 1 + + + + + CNT + CNT + counter + 0x24 + 0x20 + read-write + 0x00000000 + + + CNT + Low counter value + 0 + 16 + + + UIFCPY + UIF Copy + 31 + 1 + + + + + PSC + PSC + prescaler + 0x28 + 0x20 + read-write + 0x0000 + + + PSC + Prescaler value + 0 + 16 + + + + + ARR + ARR + auto-reload register + 0x2C + 0x20 + read-write + 0x00000000 + + + ARR + Low Auto-reload value + 0 + 16 + + + + + + + TIM7 + 0x40001400 + + TIM7 + TIM7 global interrupt + 55 + + + + NVIC + Nested Vectored Interrupt + Controller + NVIC + 0xE000E100 + + 0x0 + 0x401 + registers + + + + ISER0 + ISER0 + Interrupt Set-Enable Register + 0x0 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER1 + ISER1 + Interrupt Set-Enable Register + 0x4 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ISER2 + ISER2 + Interrupt Set-Enable Register + 0x8 + 0x20 + read-write + 0x00000000 + + + SETENA + SETENA + 0 + 32 + + + + + ICER0 + ICER0 + Interrupt Clear-Enable + Register + 0x80 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER1 + ICER1 + Interrupt Clear-Enable + Register + 0x84 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ICER2 + ICER2 + Interrupt Clear-Enable + Register + 0x88 + 0x20 + read-write + 0x00000000 + + + CLRENA + CLRENA + 0 + 32 + + + + + ISPR0 + ISPR0 + Interrupt Set-Pending Register + 0x100 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR1 + ISPR1 + Interrupt Set-Pending Register + 0x104 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ISPR2 + ISPR2 + Interrupt Set-Pending Register + 0x108 + 0x20 + read-write + 0x00000000 + + + SETPEND + SETPEND + 0 + 32 + + + + + ICPR0 + ICPR0 + Interrupt Clear-Pending + Register + 0x180 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR1 + ICPR1 + Interrupt Clear-Pending + Register + 0x184 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + ICPR2 + ICPR2 + Interrupt Clear-Pending + Register + 0x188 + 0x20 + read-write + 0x00000000 + + + CLRPEND + CLRPEND + 0 + 32 + + + + + IABR0 + IABR0 + Interrupt Active Bit Register + 0x200 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR1 + IABR1 + Interrupt Active Bit Register + 0x204 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IABR2 + IABR2 + Interrupt Active Bit Register + 0x208 + 0x20 + read-only + 0x00000000 + + + ACTIVE + ACTIVE + 0 + 32 + + + + + IPR0 + IPR0 + Interrupt Priority Register + 0x300 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR1 + IPR1 + Interrupt Priority Register + 0x304 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR2 + IPR2 + Interrupt Priority Register + 0x308 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR3 + IPR3 + Interrupt Priority Register + 0x30C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR4 + IPR4 + Interrupt Priority Register + 0x310 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR5 + IPR5 + Interrupt Priority Register + 0x314 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR6 + IPR6 + Interrupt Priority Register + 0x318 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR7 + IPR7 + Interrupt Priority Register + 0x31C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR8 + IPR8 + Interrupt Priority Register + 0x320 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR9 + IPR9 + Interrupt Priority Register + 0x324 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR10 + IPR10 + Interrupt Priority Register + 0x328 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR11 + IPR11 + Interrupt Priority Register + 0x32C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR12 + IPR12 + Interrupt Priority Register + 0x330 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR13 + IPR13 + Interrupt Priority Register + 0x334 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR14 + IPR14 + Interrupt Priority Register + 0x338 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR15 + IPR15 + Interrupt Priority Register + 0x33C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR16 + IPR16 + Interrupt Priority Register + 0x340 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR17 + IPR17 + Interrupt Priority Register + 0x344 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR18 + IPR18 + Interrupt Priority Register + 0x348 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR19 + IPR19 + Interrupt Priority Register + 0x34C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR20 + IPR20 + Interrupt Priority Register + 0x350 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR21 + IPR21 + Interrupt Priority Register + 0x354 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR22 + IPR22 + Interrupt Priority Register + 0x358 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR23 + IPR23 + Interrupt Priority Register + 0x35C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR24 + IPR24 + Interrupt Priority Register + 0x360 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR25 + IPR25 + Interrupt Priority Register + 0x364 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR26 + IPR26 + Interrupt Priority Register + 0x368 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR27 + IPR27 + Interrupt Priority Register + 0x36C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR28 + IPR28 + Interrupt Priority Register + 0x370 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR29 + IPR29 + Interrupt Priority Register + 0x374 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR30 + IPR30 + Interrupt Priority Register + 0x378 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR31 + IPR31 + Interrupt Priority Register + 0x37C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR32 + IPR32 + Interrupt Priority Register + 0x380 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR33 + IPR33 + Interrupt Priority Register + 0x384 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR34 + IPR34 + Interrupt Priority Register + 0x388 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR35 + IPR35 + Interrupt Priority Register + 0x38C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR36 + IPR36 + Interrupt Priority Register + 0x390 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR37 + IPR37 + Interrupt Priority Register + 0x394 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR38 + IPR38 + Interrupt Priority Register + 0x398 + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + IPR39 + IPR39 + Interrupt Priority Register + 0x39C + 0x20 + read-write + 0x00000000 + + + IPR_N0 + IPR_N0 + 0 + 8 + + + IPR_N1 + IPR_N1 + 8 + 8 + + + IPR_N2 + IPR_N2 + 16 + 8 + + + IPR_N3 + IPR_N3 + 24 + 8 + + + + + ISER3 + ISER3 + Interrupt Set-Enable Register + 0xC + 0x20 + read-write + 0x00000000 + + + ISER4 + ISER4 + Interrupt Set-Enable Register + 0x10 + 0x20 + read-write + 0x00000000 + + + ICER3 + ICER3 + Interrupt Clear-Enable + Register + 0x8C + 0x20 + read-write + 0x00000000 + + + ICER4 + ICER4 + Interrupt Clear-Enable + Register + 0x90 + 0x20 + read-write + 0x00000000 + + + ISPR3 + ISPR3 + Interrupt Set-Pending Register + 0x10C + 0x20 + read-write + 0x00000000 + + + ISPR4 + ISPR4 + Interrupt Set-Pending Register + 0x110 + 0x20 + read-write + 0x00000000 + + + ICPR3 + ICPR3 + Interrupt Clear-Pending + Register + 0x1C0 + 0x20 + read-write + 0x00000000 + + + ICPR4 + ICPR4 + Interrupt Clear-Pending + Register + 0x1C4 + 0x20 + read-write + 0x00000000 + + + IABR3 + IABR3 + Interrupt Active Bit Register + 0x20C + 0x20 + read-write + 0x00000000 + + + IABR4 + IABR4 + Interrupt Active Bit Register + 0x210 + 0x20 + read-write + 0x00000000 + + + + + DBGMCU + Microcontroller Debug Unit + DBGMCU + 0x5C001000 + + 0x0 + 0x400 + registers + + + + IDC + IDC + DBGMCU Identity Code Register + 0x0 + 0x20 + read-only + 0x10006450 + + + DEV_ID + Device ID + 0 + 12 + + + REV_ID + Revision + 16 + 16 + + + + + CR + CR + DBGMCU Configuration Register + 0x4 + 0x20 + read-write + 0x00000000 + + + DBGSLEEP_D1 + Allow D1 domain debug in Sleep mode + 0 + 1 + + + DBGSTOP_D1 + Allow D1 domain debug in Stop mode + 1 + 1 + + + DBGSTBY_D1 + Allow D1 domain debug in Standby mode + 2 + 1 + + + DBGSLEEP_D2 + Allow D2 domain debug in Sleep mode + 3 + 1 + + + DBGSTOP_D2 + Allow D2 domain debug in Stop mode + 4 + 1 + + + DBGSTBY_D2 + Allow D2 domain debug in Standby mode + 5 + 1 + + + DBGSTOP_D3 + Allow debug in D3 Stop mode + 7 + 1 + + + DBGSTBY_D3 + Allow debug in D3 Standby mode + 8 + 1 + + + TRACECLKEN + Trace port clock enable + 20 + 1 + + + D1DBGCKEN + D1 debug clock enable + 21 + 1 + + + D3DBGCKEN + D3 debug clock enable + 22 + 1 + + + TRGOEN + External trigger output enable + 28 + 1 + + + + + APB3FZ1 + APB3FZ1 + DBGMCU APB3 peripheral freeze register + 0x34 + 0x20 + read-write + 0x00000000 + + + WWDG1 + WWDG1 stop in debug + 6 + 1 + + + + + APB1LFZ1 + APB1LFZ1 + DBGMCU APB1L peripheral freeze register + 0x3C + 0x20 + read-write + 0x00000000 + + + DBG_TIM2 + TIM2 stop in debug + 0 + 1 + + + DBG_TIM3 + TIM3 stop in debug + 1 + 1 + + + DBG_TIM4 + TIM4 stop in debug + 2 + 1 + + + DBG_TIM5 + TIM5 stop in debug + 3 + 1 + + + DBG_TIM6 + TIM6 stop in debug + 4 + 1 + + + DBG_TIM7 + TIM7 stop in debug + 5 + 1 + + + DBG_TIM12 + TIM12 stop in debug + 6 + 1 + + + DBG_TIM13 + TIM13 stop in debug + 7 + 1 + + + DBG_TIM14 + TIM14 stop in debug + 8 + 1 + + + DBG_LPTIM1 + LPTIM1 stop in debug + 9 + 1 + + + DBG_I2C1 + I2C1 SMBUS timeout stop in debug + 21 + 1 + + + DBG_I2C2 + I2C2 SMBUS timeout stop in debug + 22 + 1 + + + DBG_I2C3 + I2C3 SMBUS timeout stop in debug + 23 + 1 + + + + + APB2FZ1 + APB2FZ1 + DBGMCU APB2 peripheral freeze register + 0x4C + 0x20 + read-write + 0x00000000 + + + DBG_TIM1 + TIM1 stop in debug + 0 + 1 + + + DBG_TIM8 + TIM8 stop in debug + 1 + 1 + + + DBG_TIM15 + TIM15 stop in debug + 16 + 1 + + + DBG_TIM16 + TIM16 stop in debug + 17 + 1 + + + DBG_TIM17 + TIM17 stop in debug + 18 + 1 + + + DBG_HRTIM + HRTIM stop in debug + 29 + 1 + + + + + APB4FZ1 + APB4FZ1 + DBGMCU APB4 peripheral freeze register + 0x54 + 0x20 + read-write + 0x00000000 + + + DBG_I2C4 + I2C4 SMBUS timeout stop in debug + 7 + 1 + + + DBG_LPTIM2 + LPTIM2 stop in debug + 9 + 1 + + + DBG_LPTIM3 + LPTIM2 stop in debug + 10 + 1 + + + DBG_LPTIM4 + LPTIM4 stop in debug + 11 + 1 + + + DBG_LPTIM5 + LPTIM5 stop in debug + 12 + 1 + + + DBG_RTC + RTC stop in debug + 16 + 1 + + + DBG_IWDG1 + Independent watchdog for D1 stop in debug + 18 + 1 + + + + + + + MPU + Memory protection unit + MPU + 0xE000ED90 + + 0x0 + 0x15 + registers + + + + MPU_TYPER + MPU_TYPER + MPU type register + 0x0 + 0x20 + read-only + 0X00000800 + + + SEPARATE + Separate flag + 0 + 1 + + + DREGION + Number of MPU data regions + 8 + 8 + + + IREGION + Number of MPU instruction + regions + 16 + 8 + + + + + MPU_CTRL + MPU_CTRL + MPU control register + 0x4 + 0x20 + read-write + 0X00000000 + + + ENABLE + Enables the MPU + 0 + 1 + + + HFNMIENA + Enables the operation of MPU during hard + fault + 1 + 1 + + + PRIVDEFENA + Enable priviliged software access to + default memory map + 2 + 1 + + + + + MPU_RNR + MPU_RNR + MPU region number register + 0x8 + 0x20 + read-write + 0X00000000 + + + REGION + MPU region + 0 + 8 + + + + + MPU_RBAR + MPU_RBAR + MPU region base address + register + 0xC + 0x20 + read-write + 0X00000000 + + + REGION + MPU region field + 0 + 4 + + + VALID + MPU region number valid + 4 + 1 + + + ADDR + Region base address field + 5 + 27 + + + + + MPU_RASR + MPU_RASR + MPU region attribute and size + register + 0x10 + 0x20 + read-write + 0X00000000 + + + ENABLE + Region enable bit. + 0 + 1 + + + SIZE + Size of the MPU protection + region + 1 + 5 + + + SRD + Subregion disable bits + 8 + 8 + + + B + memory attribute + 16 + 1 + + + C + memory attribute + 17 + 1 + + + S + Shareable memory attribute + 18 + 1 + + + TEX + memory attribute + 19 + 3 + + + AP + Access permission + 24 + 3 + + + XN + Instruction access disable + bit + 28 + 1 + + + + + + + STK + SysTick timer + STK + 0xE000E010 + + 0x0 + 0x11 + registers + + + + CSR + CSR + SysTick control and status + register + 0x0 + 0x20 + read-write + 0X00000000 + + + ENABLE + Counter enable + 0 + 1 + + + TICKINT + SysTick exception request + enable + 1 + 1 + + + CLKSOURCE + Clock source selection + 2 + 1 + + + COUNTFLAG + COUNTFLAG + 16 + 1 + + + + + RVR + RVR + SysTick reload value register + 0x4 + 0x20 + read-write + 0X00000000 + + + RELOAD + RELOAD value + 0 + 24 + + + + + CVR + CVR + SysTick current value register + 0x8 + 0x20 + read-write + 0X00000000 + + + CURRENT + Current counter value + 0 + 24 + + + + + CALIB + CALIB + SysTick calibration value + register + 0xC + 0x20 + read-write + 0X00000000 + + + TENMS + Calibration value + 0 + 24 + + + SKEW + SKEW flag: Indicates whether the TENMS + value is exact + 30 + 1 + + + NOREF + NOREF flag. Reads as zero + 31 + 1 + + + + + + + NVIC_STIR + Nested vectored interrupt + controller + NVIC + 0xE000EF00 + + 0x0 + 0x5 + registers + + + + STIR + STIR + Software trigger interrupt + register + 0x0 + 0x20 + read-write + 0x00000000 + + + INTID + Software generated interrupt + ID + 0 + 9 + + + + + + + FPU_CPACR + Floating point unit CPACR + FPU + 0xE000ED88 + + 0x0 + 0x5 + registers + + + + CPACR + CPACR + Coprocessor access control + register + 0x0 + 0x20 + read-write + 0x0000000 + + + CP + CP + 20 + 4 + + + + + + + SCB_ACTRL + System control block ACTLR + SCB + 0xE000E008 + + 0x0 + 0x5 + registers + + + + ACTRL + ACTRL + Auxiliary control register + 0x0 + 0x20 + read-write + 0x00000000 + + + DISFOLD + DISFOLD + 2 + 1 + + + FPEXCODIS + FPEXCODIS + 10 + 1 + + + DISRAMODE + DISRAMODE + 11 + 1 + + + DISITMATBFLUSH + DISITMATBFLUSH + 12 + 1 + + + + + + + FPU + Floting point unit + FPU + 0xE000EF34 + + 0x0 + 0xD + registers + + + FPU + Floating point unit interrupt + 81 + + + + FPCCR + FPCCR + Floating-point context control + register + 0x0 + 0x20 + read-write + 0x00000000 + + + LSPACT + LSPACT + 0 + 1 + + + USER + USER + 1 + 1 + + + THREAD + THREAD + 3 + 1 + + + HFRDY + HFRDY + 4 + 1 + + + MMRDY + MMRDY + 5 + 1 + + + BFRDY + BFRDY + 6 + 1 + + + MONRDY + MONRDY + 8 + 1 + + + LSPEN + LSPEN + 30 + 1 + + + ASPEN + ASPEN + 31 + 1 + + + + + FPCAR + FPCAR + Floating-point context address + register + 0x4 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Location of unpopulated + floating-point + 3 + 29 + + + + + FPSCR + FPSCR + Floating-point status control + register + 0x8 + 0x20 + read-write + 0x00000000 + + + IOC + Invalid operation cumulative exception + bit + 0 + 1 + + + DZC + Division by zero cumulative exception + bit. + 1 + 1 + + + OFC + Overflow cumulative exception + bit + 2 + 1 + + + UFC + Underflow cumulative exception + bit + 3 + 1 + + + IXC + Inexact cumulative exception + bit + 4 + 1 + + + IDC + Input denormal cumulative exception + bit. + 7 + 1 + + + RMode + Rounding Mode control + field + 22 + 2 + + + FZ + Flush-to-zero mode control + bit: + 24 + 1 + + + DN + Default NaN mode control + bit + 25 + 1 + + + AHP + Alternative half-precision control + bit + 26 + 1 + + + V + Overflow condition code + flag + 28 + 1 + + + C + Carry condition code flag + 29 + 1 + + + Z + Zero condition code flag + 30 + 1 + + + N + Negative condition code + flag + 31 + 1 + + + + + + + SCB + System control block + SCB + 0xE000ED00 + + 0x0 + 0x41 + registers + + + + CPUID + CPUID + CPUID base register + 0x0 + 0x20 + read-only + 0x410FC241 + + + Revision + Revision number + 0 + 4 + + + PartNo + Part number of the + processor + 4 + 12 + + + Constant + Reads as 0xF + 16 + 4 + + + Variant + Variant number + 20 + 4 + + + Implementer + Implementer code + 24 + 8 + + + + + ICSR + ICSR + Interrupt control and state + register + 0x4 + 0x20 + read-write + 0x00000000 + + + VECTACTIVE + Active vector + 0 + 9 + + + RETTOBASE + Return to base level + 11 + 1 + + + VECTPENDING + Pending vector + 12 + 7 + + + ISRPENDING + Interrupt pending flag + 22 + 1 + + + PENDSTCLR + SysTick exception clear-pending + bit + 25 + 1 + + + PENDSTSET + SysTick exception set-pending + bit + 26 + 1 + + + PENDSVCLR + PendSV clear-pending bit + 27 + 1 + + + PENDSVSET + PendSV set-pending bit + 28 + 1 + + + NMIPENDSET + NMI set-pending bit. + 31 + 1 + + + + + VTOR + VTOR + Vector table offset register + 0x8 + 0x20 + read-write + 0x00000000 + + + TBLOFF + Vector table base offset + field + 9 + 21 + + + + + AIRCR + AIRCR + Application interrupt and reset control + register + 0xC + 0x20 + read-write + 0x00000000 + + + VECTRESET + VECTRESET + 0 + 1 + + + VECTCLRACTIVE + VECTCLRACTIVE + 1 + 1 + + + SYSRESETREQ + SYSRESETREQ + 2 + 1 + + + PRIGROUP + PRIGROUP + 8 + 3 + + + ENDIANESS + ENDIANESS + 15 + 1 + + + VECTKEYSTAT + Register key + 16 + 16 + + + + + SCR + SCR + System control register + 0x10 + 0x20 + read-write + 0x00000000 + + + SLEEPONEXIT + SLEEPONEXIT + 1 + 1 + + + SLEEPDEEP + SLEEPDEEP + 2 + 1 + + + SEVEONPEND + Send Event on Pending bit + 4 + 1 + + + + + CCR + CCR + Configuration and control + register + 0x14 + 0x20 + read-write + 0x00000000 + + + NONBASETHRDENA + Configures how the processor enters + Thread mode + 0 + 1 + + + USERSETMPEND + USERSETMPEND + 1 + 1 + + + UNALIGN__TRP + UNALIGN_ TRP + 3 + 1 + + + DIV_0_TRP + DIV_0_TRP + 4 + 1 + + + BFHFNMIGN + BFHFNMIGN + 8 + 1 + + + STKALIGN + STKALIGN + 9 + 1 + + + DC + DC + 16 + 1 + + + IC + IC + 17 + 1 + + + BP + BP + 18 + 1 + + + + + SHPR1 + SHPR1 + System handler priority + registers + 0x18 + 0x20 + read-write + 0x00000000 + + + PRI_4 + Priority of system handler + 4 + 0 + 8 + + + PRI_5 + Priority of system handler + 5 + 8 + 8 + + + PRI_6 + Priority of system handler + 6 + 16 + 8 + + + + + SHPR2 + SHPR2 + System handler priority + registers + 0x1C + 0x20 + read-write + 0x00000000 + + + PRI_11 + Priority of system handler + 11 + 24 + 8 + + + + + SHPR3 + SHPR3 + System handler priority + registers + 0x20 + 0x20 + read-write + 0x00000000 + + + PRI_14 + Priority of system handler + 14 + 16 + 8 + + + PRI_15 + Priority of system handler + 15 + 24 + 8 + + + + + SHCSR + SHCSR + System handler control and state + register + 0x24 + 0x20 + read-write + 0x00000000 + + + MEMFAULTACT + Memory management fault exception active + bit + 0 + 1 + + + BUSFAULTACT + Bus fault exception active + bit + 1 + 1 + + + USGFAULTACT + Usage fault exception active + bit + 3 + 1 + + + SVCALLACT + SVC call active bit + 7 + 1 + + + MONITORACT + Debug monitor active bit + 8 + 1 + + + PENDSVACT + PendSV exception active + bit + 10 + 1 + + + SYSTICKACT + SysTick exception active + bit + 11 + 1 + + + USGFAULTPENDED + Usage fault exception pending + bit + 12 + 1 + + + MEMFAULTPENDED + Memory management fault exception + pending bit + 13 + 1 + + + BUSFAULTPENDED + Bus fault exception pending + bit + 14 + 1 + + + SVCALLPENDED + SVC call pending bit + 15 + 1 + + + MEMFAULTENA + Memory management fault enable + bit + 16 + 1 + + + BUSFAULTENA + Bus fault enable bit + 17 + 1 + + + USGFAULTENA + Usage fault enable bit + 18 + 1 + + + + + CFSR_UFSR_BFSR_MMFSR + CFSR_UFSR_BFSR_MMFSR + Configurable fault status + register + 0x28 + 0x20 + read-write + 0x00000000 + + + IACCVIOL + IACCVIOL + 0 + 1 + + + DACCVIOL + DACCVIOL + 1 + 1 + + + MUNSTKERR + MUNSTKERR + 3 + 1 + + + MSTKERR + MSTKERR + 4 + 1 + + + MLSPERR + MLSPERR + 5 + 1 + + + MMARVALID + MMARVALID + 7 + 1 + + + IBUSERR + Instruction bus error + 8 + 1 + + + PRECISERR + Precise data bus error + 9 + 1 + + + IMPRECISERR + Imprecise data bus error + 10 + 1 + + + UNSTKERR + Bus fault on unstacking for a return + from exception + 11 + 1 + + + STKERR + Bus fault on stacking for exception + entry + 12 + 1 + + + LSPERR + Bus fault on floating-point lazy state + preservation + 13 + 1 + + + BFARVALID + Bus Fault Address Register (BFAR) valid + flag + 15 + 1 + + + UNDEFINSTR + Undefined instruction usage + fault + 16 + 1 + + + INVSTATE + Invalid state usage fault + 17 + 1 + + + INVPC + Invalid PC load usage + fault + 18 + 1 + + + NOCP + No coprocessor usage + fault. + 19 + 1 + + + UNALIGNED + Unaligned access usage + fault + 24 + 1 + + + DIVBYZERO + Divide by zero usage fault + 25 + 1 + + + + + HFSR + HFSR + Hard fault status register + 0x2C + 0x20 + read-write + 0x00000000 + + + VECTTBL + Vector table hard fault + 1 + 1 + + + FORCED + Forced hard fault + 30 + 1 + + + DEBUG_VT + Reserved for Debug use + 31 + 1 + + + + + MMFAR + MMFAR + Memory management fault address + register + 0x34 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Memory management fault + address + 0 + 32 + + + + + BFAR + BFAR + Bus fault address register + 0x38 + 0x20 + read-write + 0x00000000 + + + ADDRESS + Bus fault address + 0 + 32 + + + + + + + PF + Processor features + PF + 0xE000ED78 + + 0x0 + 0xD + registers + + + + CLIDR + CLIDR + Cache Level ID register + 0x0 + 0x20 + read-only + 0x09000003 + + + CL1 + CL1 + 0 + 3 + + + CL2 + CL2 + 3 + 3 + + + CL3 + CL3 + 6 + 3 + + + CL4 + CL4 + 9 + 3 + + + CL5 + CL5 + 12 + 3 + + + CL6 + CL6 + 15 + 3 + + + CL7 + CL7 + 18 + 3 + + + LoUIS + LoUIS + 21 + 3 + + + LoC + LoC + 24 + 3 + + + LoU + LoU + 27 + 3 + + + + + CTR + CTR + Cache Type register + 0x4 + 0x20 + read-only + 0X8303C003 + + + _IminLine + IminLine + 0 + 4 + + + DMinLine + DMinLine + 16 + 4 + + + ERG + ERG + 20 + 4 + + + CWG + CWG + 24 + 4 + + + Format + Format + 29 + 3 + + + + + CCSIDR + CCSIDR + Cache Size ID register + 0x8 + 0x20 + read-only + 0X00000000 + + + LineSize + LineSize + 0 + 3 + + + Associativity + Associativity + 3 + 10 + + + NumSets + NumSets + 13 + 15 + + + WA + WA + 28 + 1 + + + RA + RA + 29 + 1 + + + WB + WB + 30 + 1 + + + WT + WT + 31 + 1 + + + + + + + AC + Access control + AC + 0xE000EF90 + + 0x0 + 0x1D + registers + + + + ITCMCR + ITCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x0 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + DTCMCR + DTCMCR + Instruction and Data Tightly-Coupled Memory + Control Registers + 0x4 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + RMW + RMW + 1 + 1 + + + RETEN + RETEN + 2 + 1 + + + SZ + SZ + 3 + 4 + + + + + AHBPCR + AHBPCR + AHBP Control register + 0x8 + 0x20 + read-write + 0X00000000 + + + EN + EN + 0 + 1 + + + SZ + SZ + 1 + 3 + + + + + CACR + CACR + Auxiliary Cache Control + register + 0xC + 0x20 + read-write + 0X00000000 + + + SIWT + SIWT + 0 + 1 + + + ECCEN + ECCEN + 1 + 1 + + + FORCEWT + FORCEWT + 2 + 1 + + + + + AHBSCR + AHBSCR + AHB Slave Control register + 0x10 + 0x20 + read-write + 0X00000000 + + + CTL + CTL + 0 + 2 + + + TPRI + TPRI + 2 + 9 + + + INITCOUNT + INITCOUNT + 11 + 5 + + + + + ABFSR + ABFSR + Auxiliary Bus Fault Status + register + 0x18 + 0x20 + read-write + 0X00000000 + + + ITCM + ITCM + 0 + 1 + + + DTCM + DTCM + 1 + 1 + + + AHBP + AHBP + 2 + 1 + + + AXIM + AXIM + 3 + 1 + + + EPPB + EPPB + 4 + 1 + + + AXIMTYPE + AXIMTYPE + 8 + 2 + + + + + + + From 98bc9f0afd23098a2ca01d4d6e014ce6bb5843fa Mon Sep 17 00:00:00 2001 From: KY-S0ong <156529018+KY-S0ong@users.noreply.github.com> Date: Fri, 9 Aug 2024 06:22:39 -0400 Subject: [PATCH 175/212] Connecting to Configurator via USB-C cable --- docs/USB Flashing.md | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index 4981e95a043..5d627f499b4 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -56,15 +56,12 @@ With the board connected and in bootloader mode (reset it by sending the charact * Restart the Configurator (make sure it is completely closed, logout and login if unsure) * Now the DFU device should be seen by Configurator -## Platoform: Mac-OS - -Configuator devices can have a problem accesing USB devices on Mac-OS. This is *ussaly* solved by a cable change. - -* The official Apple USB-C to USB-C will not work no matter orentation. -* Make sure the cable you are using support data transfer - * For best results, use a USB-C to USB-A cable (And a dongle if your computer does not have an USB-A port) - * Dongle side pluged into the computer +## While Using USB-C cables +* If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle. + * A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts. + * This is __can__ by using a USB-C female to USB-C male dongle; **However** a USB-C to USB-A cable with a dongle works best as USB-A always sends power while USB-C needs the device to request it. + ## Using `dfu-util` `dfu-util` is a command line tool to flash ARM devices via DFU. It is available via the package manager on most Linux systems or from [source forge](http://sourceforge.net/p/dfu-util). From fc8aa0d7692c8078d92b908ebebb4990791cda26 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 9 Aug 2024 12:34:52 +0200 Subject: [PATCH 176/212] Update USB Flashing.md --- docs/USB Flashing.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index 5d627f499b4..9d79d5cd8d1 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -60,7 +60,7 @@ With the board connected and in bootloader mode (reset it by sending the charact * If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle. * A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts. - * This is __can__ by using a USB-C female to USB-C male dongle; **However** a USB-C to USB-A cable with a dongle works best as USB-A always sends power while USB-C needs the device to request it. + * Using a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works. ## Using `dfu-util` From afea9fe74fed6e6190e18a744987b8d2d4ae8b03 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Thu, 8 Aug 2024 19:36:42 +0200 Subject: [PATCH 177/212] vtx: fix VTX_SETTINGS_POWER_COUNT and add dummy entries to saPowerNames --- src/main/drivers/vtx_common.h | 2 +- src/main/io/vtx_smartaudio.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/vtx_common.h b/src/main/drivers/vtx_common.h index 021d17f24de..80b957c5d13 100644 --- a/src/main/drivers/vtx_common.h +++ b/src/main/drivers/vtx_common.h @@ -34,7 +34,7 @@ #if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP) || defined(USE_VTX_MSP) -#define VTX_SETTINGS_POWER_COUNT 5 +#define VTX_SETTINGS_POWER_COUNT 8 #define VTX_SETTINGS_DEFAULT_POWER 1 #define VTX_SETTINGS_MIN_POWER 1 #define VTX_SETTINGS_MIN_USER_FREQ 5000 diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index 20997c2da2c..7d5e213cce0 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -61,8 +61,8 @@ static serialPort_t *smartAudioSerialPort = NULL; uint8_t saPowerCount = VTX_SMARTAUDIO_DEFAULT_POWER_COUNT; -const char * saPowerNames[VTX_SMARTAUDIO_MAX_POWER_COUNT + 1] = { - "----", "25 ", "200 ", "500 ", "800 ", " " +const char *saPowerNames[VTX_SMARTAUDIO_MAX_POWER_COUNT + 1] = { + "----", "25 ", "200 ", "500 ", "800 ", " ", " ", " ", " " }; // Save powerlevels reported from SA 2.1 devices here From 791b251586bd0221e37a3833dfefdd5a557bd378 Mon Sep 17 00:00:00 2001 From: error414 Date: Tue, 6 Aug 2024 20:23:22 +0200 Subject: [PATCH 178/212] adsb enhanced --- docs/ADSB.md | 9 +++++++++ docs/Screenshots/ADSB_TTSC01_settings.png | Bin 0 -> 96151 bytes src/main/fc/fc_msp.c | 4 ++++ src/main/io/adsb.c | 6 ++++++ src/main/io/adsb.h | 2 ++ src/main/io/osd.c | 2 +- src/main/telemetry/mavlink.c | 18 +++++++++++++++++- 7 files changed, 39 insertions(+), 2 deletions(-) create mode 100644 docs/Screenshots/ADSB_TTSC01_settings.png diff --git a/docs/ADSB.md b/docs/ADSB.md index 345af30a97e..933cb264cda 100644 --- a/docs/ADSB.md +++ b/docs/ADSB.md @@ -14,4 +14,13 @@ All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/m * [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested) * [TT-SC1](https://www.aerobits.pl/product/aero/) (tested) +## TT-SC1 settings +* download software for ADSB TT-SC1 from https://www.aerobits.pl/product/aero/ , file Micro_ADSB_App-vX.XX.X_win_setup.zip and install it +* connect your ADSB to FC, connect both RX and TX pins +* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200 +* go to CLI in inav configurator and set serialpassthrough for port you connected ADSB ```serialpassthrough [PORT_YOU_SELECTED - 1] 115200 rxtx``` and close configurator +* open ADSB program you installed, got to settings and set "telemetry" = MAVLINK, + +PCB board for TT-SC1-B module https://oshwlab.com/error414/adsb-power-board +![TT-SC1 settings](Screenshots/ADSB_TTSC01_settings.png) diff --git a/docs/Screenshots/ADSB_TTSC01_settings.png b/docs/Screenshots/ADSB_TTSC01_settings.png new file mode 100644 index 0000000000000000000000000000000000000000..b98b73c445313543b1018f3747cb5de562bd695d GIT binary patch literal 96151 zcmeFZd0bNK_cmOo!91lloH9+NvN9`&^r$&OWhX5MI$4=1VyRg@=5XZXk|j#4B}x+Z+(^x-E`KlCX6iQzxT z7oxs6K7V5@H8brd4^ilSOSpo@PyyEY};ty5bs7*`o(I6G2OPgs~$-*@(2uRT0p zAY`D?7aCrWXJgxKErjpQi=&^jH6dQHWu(s|A8GjkrZ@`86Pq_~+ZhxN!$?NH2*BnW zJIv~9%I0NPhphRi&*+hX$)9s?S>NW0w5)-it? z1;&Ja;a6mL*jkXIAd^P>eXSxIz!F*4NS~y{HEkWl#q|U?qbNeEqbZ2Xp*|3Kejw*a zg4+7>sCRXm2-xp)mh;meQ=u4-h|6EY@{pZ+>gtxh7qJ#47Wq10DFxcf%x% zk^E5@v}Zz8KmCZjz&^%J@d}NJ_2kp*YPS9D!&&u9mYg6QNDv*_4H9zn?(9=3#k%P^ zrLN=?MO7{81EpR5Z|oYJ4n1EPJ$s_((!>b?(q>1uRduk+DrfIfVy>zv7Dx*DzK?Q953K1O5}cut5$Lkz!94RiOBC7DKbN_@>W zBQMS6yw2hu<*^~b$9H4>V8|EY&r7%Y;;uszY&U?LyJcbd(*f@fTOavZ(!cG+D`kff z&goE>bIo*`mVIsA;nN;N7zv5SvCNI~oG_<}CZa-(=K3db9k#Ezw>}%@PkW7qs!h>w zFf(S#xujSvm^m9WQQ;|U-b_>t4Z7GTAY7KsM?V$>Skgp&c_GbCY`-^D5`lOzKUQbH z`eOgZ02+3n!>pInQ7JDM_9LNR%8;Wc!E%intXZ7lH9u{v$t)j2~|4GJ20RQjsSu6o(=?rI91mNVUp z^WuDxwa+5^ZoUv(d5mpVGfRoG2@N(JSz4vzXm?6RdwG|kK6G)~9v@sEh>JeY^>2II z^AVo!GZElnJ(mJcd%?~am-msb8q^5 zP6L5coNk<8Gp^V&!UF~(Li&D2*41br>vd@RNK~_-XhawP8f?qoZn=GZ`?4jOrWEfu zIPZd2gGp(@6M+mpHG1 zL(gPZ7-icLjvywiLHp9QE(=54E}oj0p5=1(IS z0knn|woX5G3Kul>iAK5F7G2Kd5ioM2tRHn>do8IWM2w1US(Mb8&L&#am zp9z^UJA731^xLGvOwloea>)VCkJWY!7tSmrM>_OnHXT)Qgl*fqiQ-f|Rl=*Y|GrRv z$0pfxjd+}&<3tN8N$w!p2l(&OXNiNkM_qi*n+fqb@hI9@pv>fEd7xcDTA&4shuWF* zkCzDi{Ru2{)VkTt+;Xk0#c_I;$Ob|WGPg)S?X2PYcHQr@V7_$8!keNrEGPgVPHeRBF~N{Gs^);QzQ-DIz+{;Z+*N_<4? zvZ4FJi(jQztJ|}0u;OloM}K{F)gx21OnZQ(mZ^HK&qK|jR&{7c2j)M=ae~@~HYP?T zhmC(aB&OcMYzZ=A2f^M8F05v;$uS$6CELUY5h;%w@!HRm4#k?(K`$JRT&==^{j&5w zUgzQYGPXB(vpz_fx%z_s3ck4}p>#FNc6(#PFKtovI{$I)l1ok#7CAzDvM{?36V!b5 zNJB2hR^waJQgM#_P7tiQ>n10IX+2k*v3r1sR!6`h@qvO(KE@yo(ex@-(`Bx!{d-c6 z{|l1ZY)7o}d&$^Xl)b2H*$@Bm9tTr_VHMA!c!yewR&~gXhiU2lfkMs-KCM>#+VaHC`yd@q3s#A^hP5%{2rEr+sUcqEb@=< z$93uD!FBx9sVYhS!J&=7P-#A7RCj){0DJ)qyFLA+F(w9fJ2j9yf8A}nSMv)!lXKux z%S0atQ9pY1iN+`X^I5OQTpsjq-_TxqPiqPoq0HNMsA{BXt?jxOTfQ~o1JE1ZMf+{I zfp??)IQcK5hj)b7bm%3kNu~Pp}*6-&F{&?+*apn_hA`}C4xmLWCh>5H_`wnF7^{tOL8(WC{&u2YI z_}R%Aet44&0KflvT)&^_4TdVS{`2aspj9k>ruV=6hIiwC`-}CCabrr7{BjjP@w0~UMyX4PvJBJ6jc#bE0dOm6_q4H|!NPopRnQHb|EX>MV zgu!dueU3R?XP>d-eB`3fd|BU~jgfl(6;>~lEyhpB9&dRe#aPg z8p`>i3VdsK0z5?g;d!=<$L)?8d%2M8*qR`&8fuh3< z3#{D_{DIUm*13!PSl^6-Ten(&Y0z2B=O$M0_%L$U{dV!}@)r?(yX*Lmns- z54h|q5cuax-|b+>^}P%-#tutT>k0ShBr6m%ymT^2MGr#z%W`M0{GM#~=b(K)OF|S1 z+kIauawmfrPCfFiNeW9R1w7p)HAAuUmrvcJL4%H5B#yyny8{9@GO{RtxbXkk_z zDF&Veo8wk8%bHI9fI@zRC_0QxF$!;g?YbO;97bJi#^mOK9*xIX+|;V^O{c%v;18DJJ(1%TmEG64oC#PHdb`Z90prz#`YyNp;k#va z#tM#uF?#mld0tXgbgQ!vqPddKa9PeT4!@!wQFO+@@nXZa0CfUWLwL zm+Xi$Kas*d_bz0eyk7c9noX24kL*T&SZCkjxO&q8^2MtC@uIrbjC*y3aa;E)Lh@H(;C+dH!A@ucRWb8(BjgK4PHc zIuOByoD{1Pjeb1}Pm8&hW_r(!gs*`fHMpI~x7I7#U0=gg-1_aXJE&1g`KZmTO0ytS z+*0}3T+R8;sMTy`)?d-IqH8(8QFgMu2`)OclQl8(zK3GxK%IV~!P)|L3e(?JZKmBp zI?Ps3hAc9M)d`{Xe&jCzi2PXC?t_LF-L=>vmpyRb`~&Z z&ytRAv4q1L@h$$mK9a}!VQHaV!c}?G4@vxgFApI6?>z6iYNjT5z;KJjGd07JPFlcj zV$8?m{(YW7$=-4OckIQ~2Wd*U37#WyTd1{GdcTaPPlVLl1{o`QFw`$ed=E{z>AB)Y{7J^J&3A15 zS3Y4sPrXFP1?7i&=$FyzP~5bXaHQ22l+*YmeJ6y+&E!0>T6??uT1>)+L~Jh1bWS*1W`6abhc>MGbW&0P$x`5Bt(%nmb z>RLBsL66Mv4DHyeVY6UWH{ai=igiBV+p<;z9P@U~7V~yD_!j%*&BGq2Pj5s8b(yF^ zqz;GPi!Q95@j@|ATaF}~ZrA+^s|j%1=3j_B;|qh8VrzrOyyNI?9VWsYP)oEBt-tdV zOwl`RqPWRzeVQ>qUR_>eB}}s(Zm#zYCUMD~+Nt-HVf8KFgkWd=jPMV5Hl?+6;n9NF znxKPfmU6{%+jWHE2u_#7ySUi|qg^#J91XrfQs64Mz9zSR|H+;nRo0VXY5&pH>@C}K z+$OKeO9Ileg4O4Y91cLgVEWD zO-e+ICI$K&*HO-q$lokDQWR>rb9X5yC4Rkm!%l0x!pWp>16=82X|>{XT#LLsSSI}{ z%k~%Cf1w^xdUFzeKzJN2p;9L@RpiV55W*}8G#6tj|SBrJVJ z6JQDAycmUq5s^6EC!Mb)8W<7gPPSD{T(DE(Ph^nf2kH3X0R0=7YeNfL3yLFo`+46c zf+$uxplem_w!2m_k;NO`r1?(Pv(KdoqM>>}cKoBquKfYK;|RiBeu4-SEBh*|g+-HF zvge-yM!{XZN0g14?#*bFhKiK;N* z&g0MJAEe*pEmKm>EXUwpw65fH8x%JbgOM9v2ssg{?RkPD{U_uzO=?t}yq+P$>~qJp zqwxLbZhOZyZmDP9*%F+s9*s=j>0h)5i!vM=g1x|MZ>R2aFFqO9c5KSG@7AG*MJ|v6 z$aJ*HEW2!2I%0QJ^hnBcB&6>qeyc>ZbY=9jAP;2HyYX8G`DMRqKchXMiMB})dyQri zA_T>0Mk&iDX_P287qIoJY3TTD_7P*WNZ06i_ubFNbaR+77WZCMc=srZ{nnaUu=;Y1 zcN|$twWj%-xEf=7hovaAD7PI|G7mT3_P2iVCyK)-h@fEEsqom*AnLc$;>1R0fZqDt z*JX`N%+1%*qskTHTk7!pNDc@6b71Uq*FH`a(=5_xZZ~Q}8|UYFH+XC{sGSqa&c9%c zElz?Lg&g00N-^O^+{0LCwpdTD7JR#FWH>gmZbGviVi}f+7mzlLCNRP>)f7>Z!w;KAWT2M{R*=t=P& zv{=l{-erdpJRmUc-yzD};~J%`2w&0=JS!+d+prdfKC|814O;&iy*&r=jJ+bHu@KsF zI>W7v!7bDyPDLNPFi=b(+Eg+`wJ!J8QMn;2`L49M?Ey9Dte#T3yw}JA&08{SKLd%r z6H%11rM=ij{7W7BI1~{*y;L@@PS{rO7T!8W*-4xu&l6u(wHHVV_=6$o-a3C}dq?NR zDi%+b#V@%TFRJJ27zl?V;D9*JNfr)H=yM@2$BzzfcLec=)avs1u765gOSTV-I>f+4-|9V*jn3n(qx$A`xOxp#K9 z$}jk%kU3>d%v(RvY&I-?S{!jN35z?*(g{5RJS}m=P z$tt`1eVyL^^>b-I9LfTVAe74Le|XCNJ%1)N zWX1A$RBU*RO-@?UY;!cX!Q#=%xro7QNrN$b1He_xS`1k1Pl&-ceL(1rGz!~|_yIKn zQHZF!HntN*Jp;Tc1loGt#J2m~H=9_=7wP?kQ?0uo^gu-dtX>ZYFc9O5qBFVBzfb0F# zhzBddiuYq1qcM;0%B&7z1RYg67}n`5=iN1G*uk-g8M8U#^TKr5+jtS~_xPQ>oF@)M zolZa%8WPKv^CzYv2Ge=_P%3P}YV}(=JzfbSb`iP}HQAp7HRh&eLPpXmr_)Ge0!=4k z<;=J=kaM?k{EH568e!emd<`C+_@??AIU}ick*lVKbEgZMy#UZ%Zp}I+e!_w`j3=E$ zb$izda8-WY28;)#hyzC{4ZEyPH&oCbdW^P_;OU$qPd#*DoE2JY)nb#FR5JThU zZtUyX+=$oMU+iLi&*FT{;C`Rx7Ffj4P5=cy861~MMqQz;_1p$MfVv|NW|wQW!=tCZ zIvB&VPsF{uzEuAPUb{U&=B%INMz!V|rI&F+b9=m&2^XwrVzek5oqoDJpn&u$rEVqP zh{&(NUuBh5uV&UZ?9Mmj>T~6UjF^S1Q+A%&WJ7U8Zs+)_+}bg1HmbZ2DD~&lGqr{C zBoKvExNtiHBu2l+%r;AIQ{^#&rcEfod9k>x>&y1>0^uy9>BTQ z1P-QuyPu1-j~6}QretihknUVxMC(r4<)sT>`1a__OLtS$R7#TWz;6aQ)J<&xTM=3S z_`@oXA?lc$a?M|z^Fqr~j-pi?lv!qBwRWP&t=Nk{j*d_>(vo;U48Y}|G=?DLro16; zoW=T*@>_X5^06latrF17P@Q^n*7|m$bRLY7w?o=+uF!k2Sm&#WT#ccM6Xx(x%uC3t zCxL}0-+tyHhUUz2qubZ(h!9G|G{&SHXLW#dCGhzil z_pr$6$!PapEdGn|x4oE4CmW^ZSi&xbLM|-4fvdoD_A3Nf^_F>U>p~JX1(>%Lh^YrF z{H0z!GSLoEB(mB%lKQc5wJ+xru??r-?Dp98RE=G0gUrE4q}9e2Mc3o}rq5UMiWR#; z2SD4>!Z}&tKSui)HsZN1+|Zh!21OKGie3O@s$*`B!gBjx4vT`_RI=9@P5xnnmHdg? z;6B3#YT)hUV(E=4!rOmmhO$s&#X|d|FG4IjGnypGR){IYws!yE%;4C#LK8uZVJcpB z`0^0W&lgsq#IH-_g|9^e8CG&04-Tczr&>?n%SRCU(9_}%$1vb{M_^_GE0 zF;aJ4?hh#I99p`-V}Y&E6!fIo!g8swl$ zNbZdeqGuU{H=@D8@U0#gTl=2Eo3erix&yJP2cb;)aYZ!hR}AcwsK1)ewKAnL%SM_4JDjAYEx^MXj^YE ze49OClC}FCix?p#xjnNdGTH__O2q^6S!&hjjFI-Pj(m%3 z#X=8l6r+Tlp{Y9>6OjY+nciU6-5|A5=e2;MIaSM;K4srt4z-!Ri5JQxDZD|Hb{XJm zfZ6*>UIEL>DkXM%4&&Tlqf{)|BE2`Xv84WG$D4W0uWDM6Df|WGeph2f*VpsBMuc@M zJ)88)vU%KFpGScjnVOXR6JEvYikX>w=4_nIS9~mpS?0pXt|LXB(b@(@E)bj`!+IuV z5zpE^=Cb$&upYADIL1YOsP|hzx4P=UGI;Tbf~0~w$`gDOoeGQ z#V}j{aA0D-vtI7$b=Im`ZP4r?moBuB*O+bD)$$-A>UjAX1Haikr42V?XP5H_qz{Ld z^ZO2qA~zT7-=qD?)3s0G*|!pBSsp3tTeg_(puL7A2t5yrV(eRi@YCh()iie4X#ifl zl&)ey-whYFxfR@q+QrZ9A;5{D1td)Qc)UpcN==(bY0*~eY3)(fUe4o0KCNgk$AvQn z$Q>-LT}Co)tzUR4$U%@P(r5F&0idE-ICN+qSA1o#oh$Zl=jf?`4;Z0zaxipn*wYZ3vF*W0s5pTWRWLLqPEfu^n z#)G~>MR9x1{7b&)#P37mXz;PNA|LJ@6XGX$TGSjwTXqpRVPlF3^5 zYEe&`RjVIuXx~7@bVyN^!T&I5YWIkXxJ(f!;v6m7>!Z_fJdRItao&@I{(3`ceP`dm z4LpYImx*7=dvY{|R|^pi@++@(USwBjx~i}i6`wUMWFdG10doVN3IvtIzvsTo_9V6s z?($Uh+@w1e-tM5@Ze%G?uar^b(+3;wO?&S4u=m`-RZO2neVdmQuur<()z2Y*o88FE z$WTBD=ys~#r7c?H`?9EO(2UhAYkIX)v$J()`3Rq4Wm47{Qwo{O zav|EB&ND+yD-03Svhram(=NC}ld|FO>iVAwaKZ|{BO~gAnx9Uw<iCXCn|tz9y)ZEC;e2^{19{i=nU#?uIIVvJ$7qI_=jrSBxP5GJ)J&3`r*m zh5%w5o${7Xlq>y&G=}(1bUEDf@-TG{K+8qw2L|-m2yG$;VE=AXF4d2eb7R`L;gcB1 zjK9z&F#lYB%TH`k*T=&v_=N?z&>GcRZ>xusk8CP67~5$@ALdHAKnzTw}I|h*?%D0UnO6 z;FAjdT3!iTDX?+w(tl5WSAa1jmcH9^{zGw_QhfFg2rnI0XXW%n1{O1@nY zeP4EJ>}gCM{-~-#Y~lBTU(e(Ui8MJ9gD?l>SsuZ&rLWL)pDQYHB}Z$xz2h%ydw+KA`~B}? zClL@f_9nY^uHa4hWy4rX{98F+h=d>T0D>Onz!gzDys_mM&q<1jNezl?*|oJ|lRhALr{*fAYt=*?lz9+XA(9-#(((yG4@{h%eHjAemxa1#;*!}lfZUWecaL@dV zF(hj45+sv`hCRZA?Y-<<0&?BFP~8mbX?Vqp#+cKmAAp(zc4M3EP}cXL>TUi2LT{8N zZLzSV?gVl6zVjf)B@|qJudF{Dh5L1Gyl23b#%U2%j5L$`X^eZy8}!7wW3WF`j%Da3 zvV=Ib1Juz#(s)eE1{H`_qb7daTgd*&t!V*M3*YX~K&FTB<<9C9npqC5Y!WFJbG7-Q zeb`?dMNN!E31{-4S3}5`D}9QGc2fV3#b1P1L^OpwT}npFAR62m zo0;pN7S8j<&STS^_h{>Q5p-m>jZnIJg~kf{=H>*^jb%!#jVB+K@Sy8IcCWoL$U zNB6=-$9G(!+N&_pG7h7~f-sx%0Y@pcCgYHtLek!+&8YPG3>z2R!>0Ve99+uqH}n1UV{P;Zro5jr_U6P{E{>u9p-< zNCMGA5BorW1ora%e7}=|GD=YOew{YG_acSN@4~3m%z~jyD(d&}@_f^UqSSon34fN; zT>+)HQ?-u&<_c<3UA=7t04FDChH!O{MG-w(A76Oyk z{Hji#_rTs0_)8C;k3=#;JMk%s6wJ{L+Hm^5JynQ%R2F=;Rio z`L-BMefVu}xwM`o-iBMrF7*ma09EF1wVmFXwlAyg#hs9z>(SCOPIOw{H!R|}MrpGM z9)iI>fP!{yk;@_akMOhA5XJG8D)qm(fTxTqLpt&){1nIU+RGo66w4L-e2YL~g2+<4 zzZD=c6Cbm2iua2~1L~(qI#IiMo+y?vpmPl__Vjys-d^@?oS)|Fmh-Lz9Tqtn z)*TT?lX_={kFx7VePWkKvifL>IZS;GHCHjfFih@phuOk{`C#k4Zm&{bVvPV>O=NTy zXVk`_@i7avRijlMw^Z1*jB5|@q5&V~14!|9pfgq7q!xidi62B1u+JCF^YY~_k=olJ z&o1IXZPdsS<+`wM#^X`6k0I1af7f~aBgTlsd?zn!$uf~pHJ=;dvqO5PlYr@U!k3;v6s&4C1BIN*ch~ z)DZFWAn8{nlgm8cvdJM2!Xh-F5$3BM)?!_|IH9A~VPm^HOQ~0T`aWF*dhOcbyP#SU zNaa^G#slQgUf<4N{CoBkF!+C8dOwO z!93MkIzDao5+omVAyP_yYKLkd?}aw(2L!P9`g&v#1q|Vy@cK>~|Ez`##-pg0X@uP) zXjHoCDWgoTA+AZ|0|{2Qpj=lf+1FPQo6Yy+*r~8eoeK9*Z58o>{rHcI1z3)j?Zsrs z{n&TcZ=g_u?qxjQi*hj;pj5lJSOkR^If6Isd1tCSXw)!i0ttiw{V*~#P~QiUfo6pr zZR6^u({*ew1-K9`hs%sKlC_Wt?FE*OHJd)Go13iQLy2>^_5;)QJSmr`o9`d%RYMU! ze#!l{{;HRqNQmzIm97Z#M{$Luw(?TB=S9fOTXexM+}J(rL34-TTytHfR#%@Rk!A<^lac5)_ASa_kY`-}|hvqM#b6GY$peZv#4 ztZ1mVL6vnE`~Y!OOs^D;^i7|LV`P|&BJi*-{EY&SVc zD9bg>0Y!Z5HmMyEGMg^L9aLb&3-N(1Ybo65scWK3^FzG88g&^n?c$I=NLup5=9A;vHv(XKd!SQE&OX6F&6tWP-v;Fn*IRP3KdEMz%Zh8(u&O6rhG~aC+ zGY++%aMS}-3uj~E72cze@ytjXVW6dKB&K?zq0g@L$*eWF0}>Q?VK_78nm<(CgFk>mqKHc(myu+okd$p=>G zlitpx?y;0$?vAFagXZjnxd=+ujZVZ&lZXR~J%t+zzf-{XM&|~mWO5;9oAuEis=7>| zNIh=WD0NiR+U`gKZQpQIYeznNCxeX)ReivrFc_d;6#}CvJr8_P_WY%hw8ylmS#Mx< z3)oCR{M-c@rNopW?Heno2w(w!Qky>D)#eYp*6zz{SC@O7r7~MIQb(!!L~rfss`g z@8?FPA>T+FmZ{Cvf{;hJxN$K( ztWo+dbUxdSq`f@?hJ2_M;p;fgFYVzyYsw?{mnF41XKQUGLI@A=`wavd{9@Y%;v}9A zFBq04sqe6F+wx!9TdB8B#o3nu*M%)le3)Ap3yCq30Y+9f+-r1S=T87lhKSP~{k+)R z))I{}YL1%)RgAY$NEBImRi%PpvnNeF9Tt{;zOK>Xgf zl^xm)%8MzHel)o_AH$aSy#$sOhnarpKpah7vjeF4N3p*gXp|0^stW8$oPfe_aUVyL zT9m5PoSj0kt_(zh#1e(*d2}Z>oB}yAI&My|o?eLBQ4n#9x99uf`a@1$#j4n`@5pr_ z%L9?^xfXC3^tCCM+_=fK(Ps)t`0)dZ;ZdVDU=Ler`-Bu?A{nO@NZ94dY{{Skn)^27 z+>T6cl-m>#0nY$auTmMxGb+4+vU>}Bmxf*~@>mLc6ZSv~=nXC7LvgPDN@tK6&d|7S zH5Md);OHipEEbZ9{-#E1?SrAG2H8(tq1oBlUGns`-#z9J$iLW)whida4Qs?(Nm@Ue zj4Xg!I}3?M*digQQu+naQXZ?YV}%3KvE}UUTvK#zD6#)a5~$0-)nuwyL((j!Bb}W*Fv_r`54UHIR%96)zM zkfhWewW})@TaMQLMeyvVrJExul`fk$Id=wgoX#n%wt@c} zqUbvrbCY=C&)tFDE16dhDCjX7K1p449{!m)D%VL9e3aFoj-mGTPrFe!Nv$|k0A5N= zHCGB`?6ZD(FJ=QA^UQLD31NGag;_~Xl{KXYpoTLE!Z5N5LhMcW>4$|d0RO@Va7be6 z7j#VkeeZT@|BJl0?oCaZ6u1I!VBnbBS@|PrH!2dW(L(>=fd0JokdJ zkhA6}O^*iU+4to0e0=F&M&~cZ-l{m$7&Gd)bAH~tK{U9N7?l7Vn>wdK;fccK zPS1gT#ZmXkvl>e(SMuXt(+|mG$R1?_($8}x!P=)mna*0A${Q6-RHXws4A9?_u!v(W z4-{++;^G?d4dBQjV3Q5^fQ)$uMsMf}s%nVF zc2-1_dOkDCo5LQY4%aPo4o3^x3AiT_T;~=o>ntH1DWE46*2jljWT?vgC7gI3?A1t= zWE^~_OxT3H6B@43HM|Dr#_;Lh=xO&jx%w4(>~o{w=)|X}SN2PCLMf+8eTarn8YH7b z)KSZ3ip5E|nDbvm9Rtac(-j0?y%yc4218sXe^*=c3xoslb%+5;C;N4VUih4JL64ekhM zJ+9K%M!`y2(O}I)5r!@ZORq0P_9FdXm=45Uv>Xb+dM5t2sS>sKBUU6;Ns`W&5YZ+! zd_hy&0(iWMbks~sU+3nR)a$U)1e$k0O|^WaF?_gbB0g{2N*2^pHD-$}xgI9mQTOU< z4>%_x=4cbucVbmIi9J{Wp6#P7Xi#1o3{j8ZLLJKXUJh=IxpW|YNR6!fglT7#&wfC* z$g#ls47`!I{3ISWS79MNNWEj?H9g1=F_lg_WP0@H>VUOhsRUer@s``5vFPG5%%QPK z?nsh|rL%Hd$`NmiG#+_T#{XtybG<(@Ct)>&EVUmf<=e{#6Ff+OvY(38%@C zUZcvuhItNoD(XA5_@i6=*^Q$8AT`xju_3BkI+M~;rt0~mo31$jA73Iz>-u_@C!nZ< z7*pd|V^H!tqu;#2BmSrC!JJbg?%>i?!7XK0sP!4|iMlQPA6d5k^e+ahz5ZNBYQW)gO6lWpvrj( zm&bj!y-CfAa2ci_i5GcdJK;6&=N(Rf0v(+OxT|JYpO-hr%+xu?J^COMeYpx=2wVx@ zbq($ED(WP7U>w}kS5uezU|j1Y71p8I4vl*EV|Rl7REBF$eUUAe<8vq`C?2Ii=9Nv# zDsSNEB55?aS((+O&+&2X6>>o~;qM?IZ3B?<_|(YCZOBUc)hm+ZC!;|b$ft=TvzOV< zt8|9W)Rs-c8gT)TDlK&3fZ%(7%Ae(_^YN%|HFk#U2EAoavsJ1Rq1w@{rGdhx_EEw| z$b;Cm=6WU1h4$%617S}iLts47WE08h{;|vU?IfWi2H_dn;DRUwz0I#IgInbQvGQ@z z;j}Eb(ABJ0)U$2=t>Tzpz~nOcf&BxI&*R;T$4vu_{QFts(p+QaeNKnv*lyXSx_3ZP z#_TM#N8QN{6nq!z4+^g5R$kQ%A@Lp;B%ly|XjaS#VKD-=b=5+LDXU4Ky`K6Mitt&% z|NMHWVlwSMceAHsw)_hml>Zgc85MueYPbJU{C1=Q-+}UdVS1j213s36UgHqkb8Wj|-S_I<`0v91aJ(qF+0J1f$d!2W z1PFi$9XjpmcP>sy_ie*FMi{5LJ6rP_B1iuR$W*j52jP@|9B9YF0imeDXM1DJ_@wbN`bw0r=Z)pRMR$o7EOS!sf%SNeZm~ zuQyqjpNs)xLKbU=zkj}sBMr3rFSL96Y$Qw;`pj^#GZUa6XKQfs%?JP5Pxzs^vpdc0 z_+p>l$-G8s)sxY=PAKq^0}HgF0V5rw02o;xtoOu)c((bKzzeHwq@GKoRDOJjBv7Vq zR~rvdPkTibe>T-*`?q!XQm3m-zF0FV%<8oU*8cTm6`ye8`QwKc8+?u%q7A z+h^%G@v{8i_i<*P0ifaTF7IFM4ywGIDtk*JWp$>=s}q7roY_`=f-Z7_?K2Tk==N4o z)f%E1htWn~Qx$xSKN;Y06~@vUk#w6oe5^F%P#+K|ysCST-N5VGt-b6g-17&aROT8^ z6@ITLSL0_&(-K+kwL4U4i+^})-nHx&jS|AO0NLo0R$Bx6Ik+Hs z4r8>g-F|+HK0iEB5{a`~|J{UF;ct)4shb~K1hx7N-gHqxWb_Bb=B;_3to-_(!FI{T zVV1F7p@%HdIK&3;<_ST~vy~5qF# zmu|IY?GUFolp}NK^50K{jx0=|+RK9i6yA%mN98^9C5)NhVrXt1#`y24;XeXowdvcXT!gSoke@> z^uTt<)OKa>4UhSIncQuGK0N7ON-&JVC5`#AHeW+*K=<0RZw9l)p=r8%Jj)1lc!aws zy&j#bYL8pL6dfQt@qlunDBPUy~-hWNw)5b;Osrt&G2yS5=3Z>t&a8nsEeYD5& ziihW$pR?Bq!N|H0b{(Z~Et}G9F}W;Q%;$3qW0uX)E@1Ix&fYAyx8JAAbMp@~{Q3mr zI5S64PDzQR3pU znfZ9|D@u{}Q}J$H!H(54Y{qN^vQ{Mvp(UPYkz>>f;K;Y5>beRDE0R@+jx-Ka(eq`29p?uj4_9P4T0bz z^z_Tip*YD%)m_FxW@gK?^T#e;lXDq*5kC0dc^JJ1ypS1c%P1s#@D*x{f^>mya?TF) zYs}2Ixsz!eP}nn3C@ea1XGa+3y&T2a?Fwae>+cVbmRp4eDOYcWt2v&BrYDC3Pax+! z91*TCyG{edXa$8}UrUrd$zMJ<`00&hAlUADk~x|@$tto5e-FD0SlpYpzufF8(+KuR zDFVAU5Is&@-<=6u$kNqI525Kxe>)ldVbm7nYP*JBoxW29wYOjPjW?Ma{LmHIP{t2Q z8$rv|53|4Q0DUBqD7XIkV|oR~@!i&KdRL86j=qiOZY7!@0_D037O|v$Y{K6JY7hI# zR3?iO{CwR7uZc~!<-nRLVcm7q`q~4%u{Q`d2_%BIG?US4ojo*AXtamDBkKd36rl+{ z+Ty**XXdfV7Z!;?gzPODgb^{+9Rd37hnxEQPui5z7Z)HZHAP}PUu)L)Lt!smp|IDi zzm82B#rdUjS-n!W)_vb(zvC11CUY>JO~KI^$}JsETU)Fl@>|5LcPbIj@C$luW?XJu z>F=-909($xTNdfXn}&!Mg~}HV!-8%rq%kuZ(A~vVkqBvrflK9x2>1BB_=$H8WtEaX zF%CxGKOk`uHBm1`g*wmKjnu#7r^hD@5szBr&Dx(H8D@3p1+zeLRa_)wQ>}0Wc)h=0 zEfwifw<*g%{oTj~1DvY9ICQ)4O5+2lDd(q8v+MNYT2Hcs*@PkXF>Y~pAEe%69E}L- z&PKpXYj^tLVd8bR#pM+ZJ}$mX@(%v#?MLMCB_m$(NGGUu>xBZrq~?{c{pTyeA6P;% z(Fj*l(ve@ELsG7372rpckw0pi`~ zA@f3~H(b=}ybI^LU|dy$2Np1x%&!X^#v>7BOb4JmE{#SVOFLN z@X8Qo8hplq=r3sj$kM{_*Hb(JE$d6tB zO5jonJRF#+_=zOjd=QR+zi)8mu8yy$=u#-iN}yiY3gnaZbg;L-Z;bJ)Am-~JfEAd! zId)uF_pEVkKsB+{x-B446gppH_2tMI*2Mp|35={W23o8>doTa^T>J8b$O?=$l_(K% z;H2nPM>kRZ;$8SJpfxD(Qo!=(lfT3PXu}9k$)G1W+w6Yt_QUlF&F!?gqTX7i-e{Y3 zvZgA0jw-eJIL8H;Iqv-7=Gpn6a!<0sKrX{ZS)Gz_;fVS{**!7X;%=&HRoP(EZy5EI zP~!C5^U3lYe)Ex{#IW)0I+sVzQD)ytOf<@v|L_SV-7)CQEwDNDjd}X61`l;#$%BX> zwf=~>E?GkeHfCkosB)U7LpkqDVug}!o02*nV&%TP)WNpwyA**`O)C~hZLu`vAZU`u z`5zAS-w4-VKtbBVlkyRfPjBmC$HetdL8Y?e-XbBP>jV8Z4+@%WP84f=9m$&MVDal; z#J`MAlY>1?R_{bCL#`X?!L4CCQy0$lXdC`BS|d6CHco!M)HjvQ!eT*fhh#ejL1H;{!`WV8~Inq0V6-<-c zjPx>nSBMxZt=(Y_fQhR*7awOC(Qb6mPjg1CNk4J_pp|oB80PuZ_iU1Gh-E5FDy*NT zY0c<^nc+6=%qoD1Y%ROxshQ3^f*-zhy?3o*w{O3*Ji;pr^$N6}P7p5R$jo<2=GU{z zj(K_-gB|NE0?WA${!vcnVH;E-scHb;?J44F9HSwxRw*@*s*un?-9|N$AH&6 zjzB)ft@c{)pXn$_8v5j0!zO{Nv!$vGXQJols|v&z_Wz5x1%&1K(X0W&+~npPg<28q z?+bRf@i?!g@A^ZRxj$!c<~Qe-Me_@xE1C-VAXypa#|^xEPsXwNT9eu*u) znkMhcZxQSM>FGX(%hlhD8V(Nsy!h@$ET=Jcj1B~4(}E@sTlest&&%DYRoFc8HgvUO z-^@fkI>kXA6i$FiQhQB$Kmpu1=4c7Wa;|nSOB5JGOD+u@|MYB&ch{|iOUu|fSFeRZ zaKJx5y6B!Cw#5I<214)A=^lqWdbLyuS{*K0E-qoD zVWQ0^nor#u4i(eXN41$69Sl3l2$Lc$(0@2O$i)%V%emV}y5jV1pLYrNbt+E1x8ila zC^CR`3K+m&ysH)yAI$253j}6*pOL1MNfrC1K{v*(UA8PN)9fYn{h>(2AK?94L3bg= z*4L?^M!mI2zvL6VHX~-`pBE4RoK4y6NS11b<4oWRylgW%M>}Vv>~V_@51^Yd`3T-J z2t$-XR?p7$KuRVKv5XjwwCeSdtw-;hg4UyDTRX1%>Vc)vPMY}C2j!p<_2sg=zA*&>4sYRyjxN!D%e2~Y&_FePdyIg06XN$KR zYHhputLJi3t=5*t!>>&hn>Umyddz-37Iu*1hyNxStASob;jI7}KrOJMg~T^kLIR4a zr&FHp-g|Hf!Cgxv(5UZrs|uylYNlCYP!Czp36tp zs`vMc<)PN44~Q`0?dN7Db>}Kw#vrtXvaaHNd6CC~-vDKO-%a&1mnF=DoK-hhwR7PC zD>oXWRksGWG3DMwlQ9*4%39!Rw?=J^H!&ey$$MRud8EpPI$G(Jy6ygE%&mXSVSUdD zso||JLhx1WP$cXhXyWRnLls)YAsaYZ<8$gg;xODsz06?@PWdBcWmxWm16H&SewTjW z_IBo+R$uKk860tTKJ`Hb5nv#1YOjMiV_x~KtlrhHP3p=?Ge+Kb9S4Cb+pp$(O$zNl9p9EWhX?Jq*T#vksB->SFb$dtI%VQeleaCqA(j3k(( z2b%t9Pf36mi@c{k;Aof`&x>^MeH14;-|iT&rJ(tI>~Un+N`BxLkOW^rmET|tS9+he z7Og853&Hq^yQp_!ANHXs3SdmnVH-q(mtmL1#~S&P!YrB&O*lbWO_bugPPC`G)DPFA z!Q@>gn&U!I<^~90&q&#HYDy381h9;MN)~xWk$>?7%<|Q#c2>YBX$mW`aGnbeU|85W z8UgC*E_DRz+|-fIk*sN%w60_ABOow}?g7+(cX|L-0v5V7ch0-L}HbFVy?FrtAqG$p17H_TIU|HtRgM%r`6Y!y$y z`6T;GPuC3C2#9UFAg6_af{|r*(lzA7kg&~FI6P7 zAva~>PmrVCAj8Mmo?32VDpZ+!;QPMm1N-Wgk4Y_G#?9Iw|d)KrI>fRyqd!qxuQ((F?AZB~=v!U%-?i&; z`{c29Jv~G1K|Q^jQvMKn8W`H5gZp-VTqif4*Jds zguH2)%e?ZB-bfvb4x>)@W@}XG}y;r*9LMMW&@;0O`PrX3p;d^r;LYA zFzqropNp0?W9q?1;U9b4cz=iE@8xgb$}U5HzoO^AHcBa#BRj`!aFlQsFK z>i0a4ZPXBJg^6eqm^-G7Y{}V;1(0t0g79Hetgry2fA;qFR^<8qQjnu1%e%fcty-kw z{E0GlWX@GXW9lz;E6Gy?0jB}VBd@@)qLnz(3xN>u{vb!*s8uEG?yJ2FRIc_4K}frz z?&~UVN(|*;Ii`D6C8e7>Ck;zRk`M?+;&ql$%=pVbY`GE{ieymG^ww>i{1u=Klp(i1 z{&ho~ZP%{s{S3s;SSdW3A=1dZCNiwHz3)N9#ohYv;0eEM8WK|fmtC-L`XAahpCZCY z3|CL`5-$RM+fvU+UO_qd(|G=WY9WsZp$^7+YI^^6G+cG$M6EL&ILDxnjl0;fs%je^ z{_Fu)+gx8$`K|Pn*7uRl6EBVn2PBFZP0O|PpSzW?Rtt_5#8yRXq9*7;n#P~M7Joul z@4NANUjGG&WI2}%Wx$oP^67wB%S*A^^J19Q*O&B*FP{)KKF<&*`kxhAcj?SJy{5M7 zY!zbNtHQ&uNH5-Z^Ygh62wR$Z+cwahfRh~{e2)k&aZR4E-8$Bdzo>dGdcXDy>7VD2 z_;;gf#&;|i7`Ls`_^y>Ee-E6Y%218B%U+=yMbjPGpxb=k2rE?3pYow~`uocG{cd#n zL8D3y%7;qq70e0j<}bknKsH29ulhfZ;peZv6izBC4qg?1PgE$Oj0dRvR!1inBDy+s zkaz!a?$P0Uu+ASC2B!Z9AQ;%ZM^v%?k)cvj8Y%p5gfvj~`=f3is^8$}_$I56?Os+H zVjWXv%w7XfB&Px0y<%>TZP>pC`tQnqc5f0a9DTH7=&o_M6QQCF!YQ}9o{uZ4zL)DA zbug>b3>_Njzkzw@`&rzeQpm*gt{!R0+n&uPUBzwv$gcnTaNzaWJW_99UAsL)2ve`U z(>z4-?$-1nnP1-f`Sz)I#Cb;`d5I4W8VUMKhZ7YpNQ`d2GclpvSYElJLMRWgGTe~% ze3+~V|JSVGL86|DFwXpGd_lb+f^jp0H6Sgvs2yg-eqgAQMRn)#ZNXf?D- zg!7y1y-LFOYZYRtEb)Y?CGvNq!otb)jIlK82jmye4ph_us(WGCe5)5*+KeSvLfhQB zii4-Jd*`}~+t_!%QtVI#BI8y<*Pm~*|K0PECw{0$qwch&{Xy^OrRMc@SBf(n#ED3$ z*x&jc$589vjHmYhrdgHGw=di3r|uB{rn0zhKEg5$nD26=@Sc47`T3hcQ`svnwbmUH zKibSy1Rd|xm>zDeQFF6Ie0Y?3$*{bIc%Tn*g~0pZc2MS=YG3Wu-XdG7%rNX#J_3Hff-VK!gnP0xragzF zle`_V>@!zB;`ayjik!@Mj2e-I>YaK4&?T4j#VaT>*%j?kq(aI+Dk1le5fDMLlPKjY z1grNdekNp%4@TA-U?|Y&Fj`LQ5(2;r2^h)oS{2RjyhX8j3%}w&77ucDb?fn)>N^qJ zeY#D1qM?$uP za&QN4)!~Npj## zUeH|8kyf=YJLDtI6gz;BldyoCy25i>3qHn!KnzgNjILj5t57uYFk1CPdn#a`C#8Bd z$RH7!h$HPYV*k|^P{6@UX#MmSGLaU5aU+zpPR0wc+B=ycIB$a3mFtH~EiH!>&2+RK z;0b>TY9?I<(8bSBQrO>i%>W7&0Z7Y@gO%Nna7-i+Fraul9ZcVFcRHvVC@1MnjH5@H zlN|sBT4!11KUJbVa=1qojKHkso~AfF^}p&Aqx|z|f>qB5c(e+x&rGE1|KH~L|Mk!2 zVT1p9F@5-sTF=h|Ha@H7C~hW@7~d^D8%%SJzJ2BDrEtq;t&H_714L;`zyNc(%E!+;qNzJ=Fhp5)6ej7%Y7Nrn(OIjHZ)?Od?4Q2wd>jUvM$Ii zd@ek2esv;R_09)?dYC%J5r@h&AnUUNW1}_RZAfTMKt)U~jP6xekF0B0O)WsG9$Dxn z_vUH=ifm%_49`E2^Ht5P9amU6AMT-)6twb1X!G9ka5P{aAquJ2rm_A7Dp>%omOPbqm_+6iV@!HeB}^y8O!M6$Q1jy($}7w(&ejvQ`- z9&NArdF_kE#O%DgdpsgC8nS-=|NJiKoo)p!WjTpI?P1BsD-zg#pfz;&9_eL%x zBc!vJdjXm=;y{F@`Hy;8EYJP@`#ZvN2PCf|c`@@b@jbN${u~BJk$&3&0X2nfz=QZu|iXsM8nqz~llrt+eZ0?a_{7nkh233=O!Q#rq=SC(b=%qSF_iqpMJo*8ZO;0-O9XB=SJN&-TkAZF}`fEo7M^@2y0KjjuzFE<|YE zz{$|B3Taw*Cf(RbwOz?KszqI@4Hh~&d4qxSV{A=%KEo9}2b*p}ei^}P5CQAAM@ii4BBJ)-zv6G>$bqQLVPGMQ@v@P_FW&f7Ljo@J8nmn$?#_i>mT?Un*6*}F&^gWp&M+B z91S+(F$TJ#t|tJDcB4IDyPWAvj{*LK2nO1n&_DqsZit)mrpztWv}C2qwj~r!WY=)_ ziJ?SU7CVBtI#wxO;;Nt_#4+aJ+)3!kh!4b-7WJWmtfiAR`0JYK(R+5LgSqtd#EY_~ zmFQX1T_1>0gCf2)VYO`16{mO4>`wYj&D7P^3#(pPKW%aQSx^&fr4totLNkw9*$Q7v z484lC^$Mkq)g#>=b4YC4T8sN_MMzD)*DVZo8+YY7phh!O?UGuI_vTsT;FeI$j6OXt zk}BCvF2tY$`Bm+@`3tBwlc^aQbuclok+D0*+ujmownfI8YB7;e9Xt6MeW)Hy;YfLe zTNSb&d&}M4+(7eD&6dCw<$((r`r;4P2Y3Re8-XXTiaku@kVU5p^#MK+E$i~Sr$8U9 z_H}nib!hKUr$$%9M$Cfv)ZyxH4QY$+Jbis@)bq))!&U42JE`FkE=0tmR;-ZMrb&_awOH+r@Yd(xYCB9j4$C*YtOq)S` z1~x3Oa7a~P_RV3Y=qR2u%;o#l2VBGj@VC#yS%{YSRD&r(-a-RNJ(pjG8q5@%yU&OF z`d{>SF;xX5eI~yCqw2oagC%ZDTO#OEmo}8EU=rJ>wQJ**y`EeGL{Q$2+zA(kuQL+g zsjHyB2u}INeqL$!a@wC0fOXabGy@54{P|>i!-M{Ek84l5Rt~BBywCLvHJGPzj?~rY zzT}Atqr>eX2lN_rJZ0Q;Y9tDd>{wD$EruW|Up%mvTSSDS)CzBcNW4{%wTBd$1sWHN z-~{c}#Z4dmtS%% zJvtVc14wBXnZrgt6_1Wk2Scb-3PukX_`&9IJDi7=;47;FY*)|kw(I)QcI@?RcaMOS zVx?T5^Rua_!W_l-QmzHk&5!mpY_WK`z^3P>q|&r1?ofF!o!!{3NdXe?Q@Xa zX858>QJZ32T=!PBam}83wt4mmdMa6T%g#^i*$dY4l0g19lY!LKNTzV|`PAA#?A{ZH)B zcFXcXVa`Z52HPcw)t@tXvP|(tW6#;~F?mA`;@7$beTDoQOrOdV=q>jndPx+=&#yp&1J>*;l=Aof37_x-Q) z3IgXvuDcN!zNlqccO6NBs|LMO4c@X=vI2Ym@Yu%MqDb~N(!=_2T4IMSU38_TX{mZ; zq9_(`f;+7o1o7h0_y7AefuR#xh3Fr$Js$NKdj_%`Ks)n(>^=SVDZz#l&ey@+Dj70G znRIvT&1RonMboF+n*qPhA9Wnh;dU4Ok5($>mI{ISnnvaSaP*SOmOQ)Oc>OQ6@{cw7zhCH z-^vz$&nl=9US)hd&Cbqcu#=%X?PTa~z&!8TAB7mtM{!o?kDk)~k6^|Egh%}RCt`lr zRwnSMW2gV;IsS}b8t*dVm`nV>%hEm&G@X}6h9c(eC-c25_0J_W-v=Go5}1Di{m;3- z`<^R|5U{!bkq$J{xZn98;{Tsm?B4^b$PD@S{!0)1P8?Ra6NiZ&Zr^>m-u0If*#kQ4 zU98U;kW!xV=4$Uoz~5KF9OFPjs{UGLRCG53cD{KCL~uiQwV@Y|cck2qs(5=p-~JP; z?>&+DoT#VqIKxyBT0Hk&?7;Y4L^zD>DoDtG@#4F&J&Yh>pZ^X?^wgye16VLx=q@jQ}V4^lHUqH?JMr#zN4#$nrC5U zGuA#H`a(ij^OHVw4(FWyp*p7#!uK2{oX?NtjzhQ>w2f~~K7!1(uKCTp7LIXWrXZfD zmznB`Hn&ctsoCcjys9yH_Q0=g8gsw2)|5}CU+2Ev*w{^#?Z=Zd{Iu#D)kx!I)uQ9i zFB?WXh|Szt?{a+&-tS3;R3=%3L&zk}|lf%wiuV@Ov==f*Wo{neK46rhcZZbtAA-939jKV@yy=^@N95|``~OZEz%YjH zbv*M|uc+J+&3ul1?!C`mCpX+wI(z$c+aa@~R_}#)E(*se2E&92mvzb-T+BADKboH=GtBIbCw=(OnZ zj#vSLzh>Hbm4d0oXu>OkiP{J#OVfox@h@`&a32Zu<7}Rr@o@bgl0Lp4kc=cxFq4LJ zb78)MNv3syfV+7FL`W4$3_Kf5)9+M{EY4Vp^K#r<*dN#7cDB7DWYFib9T%$uS^tYu z@}Jr@Tc@wbuqE<+J?OBKy|9a%>a%wl^8E3qEmW)@uSG5=-6Ay z$Iy63BvsUr1o-TD;Y~O&;tX${XD4L)er7Sq&YHHY-zaaT^f(OPq&3>lBGYbKcT8x-?!$$6j-DzVW{wgx-&hw%Pf-PrJ3OH0tg0H0 zR<+z2WI!RAx~mDpbh#nKU|Fk%(`pDwr;h=FSQX$cnQNBFL`2vVMmiJiMM%1 z^09pwxoQbD748PVPm<$X_R%+ZztpbsawfZWZuOv^Dd6toeUkMB(zo63dc)6kTQaUHyWIVK-d*_E->J0~%e2g^4#_`9 zUR|)d{Yvl+Yl)im%q)qCWB&P`uE3A*BthtnMXsld)95VE^^sMM$t^N7HB<52w}S&V zXjOx*<_45^=PnuE(@(sf8b`&qDKzJGUzo*|c1|jE(5=&N?eD~YrE>))e*`sK&&hzS z9Ncc$7}_Df!Rbyt1nvRUD703iUTS0l8)qs|4DQd#rz8W4epMras%fo7<3*ZB3Qrq2 z(08SqEC$E@2hg&?VgAInrQ=r`^toDuLv^m#WZs$*0FetN&PzqG6<{v=rYA%>FF6%* z>IN{WberYGBM3lSs-=nbFqExW&0_9!1b-=DP?voNYXT6ukM)$P$SIoE^O ztpg34Svz5!tL%EkA@!-NMo;UViBLVQN)`22s7Q3!1g>(o;jNbs zH8en!)T=~I$T;5YLv1%yZFsu$C96YuW*0HQyRBC1TfN`nyOE&CZ$6GTd8J)D4*11h z29$J$Q7?Am2RDP6XY9M-*c)0s_tyZE-JipUZC)*$RZ}S;Ej4(!DEKxF)SAEHIxS_G z8zdV4<%~{8OQ`lY&Cj#Y)#hM`F!v=NrmNekHN8XPmq(uae)Mv_T4IBckWjx_tpY} zW?XD9)4byT+KKSVSzooA#YjFs)8y9@wpCxU0}i+AQQp6z2qb7|WYDkpXRq42Mnn{Y zRb3mawokr+E$PfpA!%nH~##MbEdI_OiY2n%RuW zFPV_(?h3kxW(owb6J1HvXuR_HL1N)MiuPji*t^y2|U zv`KN7IJol)%WPVDee_gcESkcZZcx8oaK1VYT&}H~rU^P>Zka~YK7|_eb=jp*&uU1j zTH+kgp^-X4H~op|6rDR{&T`Nn$}9akk=03v;J5lJ%U^SqvyYd(y(WU0^l*ryJ@w4y zd5+bU6GKNXq!vis7c`zZINiIz`;>qKM!?c%#*CS~uh;SAf|fWNxnmX5Q%aSl$#0)M zIsat#0i`$F1(DDbIJnYB)zIjzvS;s{HP87Fy@#|c>E9u}=3w=pS-0mCJw0ceu%O^u z`k>PB0-ZLc?0+W#qxjUXgSBK+=Jdd*%d0!%>s}3^H^f+#w1Y_;SKdH;Kb-FEiG%Wl zV(TkgGme*z1!98z3Kc`#hw;#|1c&6b1WfbUAw*t>X*Vd|R)nCP)5w;S zt;Mu%kXsUMo~V^J(tLrcaB5lAz^|%AEr9zul6n`5_c|ILhWC8x7a5gS^x7J?$u{5T zCmZr=cbJdWp6$&RNQ^ml#hR%@3gce~B-d{sB}f**dmyu}ho-?^dn zjs9;D;C*109yZ)jl3^EI=gT+X-CJE!`h>%MyL`iDUcKQ>PVFm6%v_E>~6M zJ*>0E)O+s17vPuhhZ5Z}s*3p|I-;%+6Ih9R6en&XV7aTS#05n4erzHB-{KrUszk~=q!wQ z4Q`zw+6~qtQJ-k-_2@9(rZCTA76ZG8X~S~V`I0-=y6QdFcG9s|?DW}?b*uC%OU{Y?Bylp{O*k)t zY0<GqF1Sq6m_YBk0oh@&a0YFYvf6w38xv`K{R|TTFcc%v9Jhfgj-^E>Ich&O65{ye(lPD)tbWFjVUoReYu&L1*{ zIX`3M_5jN{*aaNhbuHA~0yI)L>u-EehP^$E)u#8AV3N1(C(2cp@#ItW&cU=vS*5F5 zCkr$hHf@IhlvFtGvC3HxO|Xv+tZMZEd`^VTebbq^Zg!H$aNANmoaqly>5G6j`nvo& zCNY$RAjB+Xst5rmn;&Z)5LwfXixLhuTng_#U{i05WR zU}1LG1J*vvk&QDZT^Cqt;|=4Xg-`rFQlohr{qcp}vr_97%M=OoDsT{a3l*A&>I1}? z#-1pI?wvu|w(1FC9mL_y;j})#_I3T_w6B)sF^3v{WPRhd6^D}zhweuC#zyb@`~=Zec$bmLUshlw@D&25 zWlWDc#G*J0|AxE)S{K061V))EM+Bx#6C6h7@sr2MbHSe2^?+bsrANG6L7@RDZj{Pd zzns#rbsIl;LXUq6wOQWfR#vQR5>;O+KdXFR;Y z8>bugViLA{q3|6wE{C^WX!r7)$~3qHoTaVd-jcT9jqF;}EkA!Nbe;BN@5KvUNzqs- z1H1%&!n!omGwHjkaXh;Se4K+MvB3^*APLJF^*oF5F8I>$E@V4mV%L_I-oMP~Cuz|Oqr?%|Mb)JEkG?UuH^#KkF)3aIDbs4diU9mQe z3?q2C1jZ+Nam{dcI7y1(#(dQSELJg5 zfm#X6tQt+E2w&SrIa-Nx>;4z?UqM8oW7s2-#P;*oZ>-*vw6CC!?F*7f>VYH$Lq^MH z3eC2pV1$d7*rOxZL(`kq{wUvugI{be(i^v8E<>y4O4=daie-tBTGlSD$S;-v`|HEY zvNmJZ-2<8ew&d)Kh2^Dg`7HP^g$kUOAt5fI26!CtEm(}jPtN%4-h5S zWn*%Dg2G7&$MyiVzp|^&bPcknw?DN}Tvi7baM8c;)4hj9bwP(wseb-}RX5+u-VO7PaZ<^BIn-4LMkr`%Wuh-!%w)GKEF;i^(^uu4r6PS3LyCO5#9834Dm=}p67oF|B^AI% zac3sgw`^@@>wG?J@YZ~z-F@nDt+qwhETe$^=G1So0i&S&=EHwjjOpX;{`mIu-VW*e zMsG9wD+g4ySq&$AQ-vr(I67-uXSWnRG5*^CPcC!O292v{RFZQ_T?}n6^BfpUmE>H| z$XRkRoRwaJ@3`{+-AH15#93%<&}htw}w3ZsAL_{1n#-~NCyIbUhnf1TWN z({8K)HrknOh!^iNcNUB9A7A(5qkHxb&S>Y-)7n%n_4yl4H!J2WHm@&~+1(GeHt#)%e0TM4oE4B~gtW?XD*^k9fIm#Vl>n*;@KFxaSgS<1T(QRzE3t*-fmW`{M*orz_ zrF|$A2e?a8`jkFv05s62kk7Ud`8mh%qRb$5UZU?o^f8C-+$)Qj_oXCPuI*My9EL5Q z3A3DfAb3(N&m9sHVXw3XZS zrhy`dnv(aT@z0i&M!~;p@0EaTeF$7R0oe18fZNIP?^mUoZGp>BR_TA<7H3RkdB2B+ zGbZ?64ztbfpRRD}IW!sRb;bn@(BD1jc4+!&rfY>#k`@!Jf~7d!JPUR@FQHZ1bDHa+ zjcS5M2vjdFI4Y?qFCiwLP%>eDtok&g^280J8`(Nm_TN7Fl#;3hp?%Byes`T_1RLKiYCn zf+t_%W)>+jGeW;@)M%i&nH)J9uO0iQLv=a|(MDgo{^YVNj_@e()Hu8CO*1rQn$ zc1J^7;Y2;CDatziS3RMDgtuvbG5)E*U_|J1#oPYb)a^ZI@FmKe3#hlp6qB&jqVB~^ zjYvHtChA*Jo6MA3filtE@Wqn;vKhLvxz#YbOp}ly;qsSHufC^>Wvy?Kok^CQ?WFxg zRb^L_3(hmm5tpWrRb8i+=RIC}Qc_C?R>xD5EiHI=z zpujSHQu)V*!1#PtXB>T|4pi}|I_&M1S+~UhOW6c;1v!MvLE1Vis7-jFy9*tc(ufeV{d zH@SI--B%z)%zin!vkuO$?i5DFjJIJXPLegOLsuO}uc%)V{_5K~E97KY@#>)lTf8+L z;@bIED$A71PDkMeCBU&x0_R(9cTS{$x;UHJW>o~cpW__l&z4+1W9eE~k>^QHD%ao- zbKoziE-5RYQ!#)H&!lfexLa)x)RTEt0Q33ghxe-b=bAJXs2}f020W)Kw9+e6VXFC` zYsrnkIe(Ommo&$k(9Rm~VXePJYvW6|UK6gdazTx0IJhJnJ+ydM?L?UM!_8}lREp!N z-fd7c`-H23=q^=VqrpsVDlID>I%r-oC8?Ow0nD7F zm-~;DX3vo>)r`7M#js8Onc}Y_CwP>MZ8R5h$^Ih*rwer78O&Ej;_`S&s*KXjy&|jg z%k%QX_nM~@WAOx%G~L_RBhz?fz~70GcsDu^Thv@WPh7Dr%_uZ#_Me$0xFmXlixdxP zCPGB~+sXmrUA~EJZedCP98#6teS>vcsU>`hmzmfRQQMPmovn$R!RTFi;%61Q+W&Y& z$;*{_*>yihJM$AC>zu>Jb;Vyxs#f!D#RPN*oBLn{5=#S_$NVvofUWj)Nw)ap<3bCa zgTJHoJX;*;MmV_K)%!r4j60*Mi!@2*n^_=oJJ|6w8@gwCEIv5bMh#rp#C31dTjQcB zzSvgV=H9DbZU+^+Gpc=K}J>AKsHb$R3X1dx~; zxCLfCqk;s`aQcJcQz~#44lXf94}F4!7JHuwO%?^xELcX}>-SH)D~=iOrskY(?@FlS z4t)OrvXZ$l=#ZfG%3RDzq_o&5S>$Bk7bQ8p>!uGTk1+ly=vtd&>k(X?Xcc_LJ2XJ*Y>hCYhG#?pXaFo zI^EwIHM{j?B56sP2Q^a~bd!UqyqC>n(k1%o-TnK-*oChMZ;PK=BfDu8!>;T`9YyYUjX|niKIl1lBxBlW)K#X6t-eI z^iEHS{j-Ai^RwGEV)wq56md7OX1XkJ@p?#=f^9O z@2Zr#6p!80;Erc$+;reAGF6msHG=xeK#JLLt(KRCP}v$3DfBQ?a(wxsDIukpcWlv(J?rK|y6f-a*@1RylQA*3|uW zL!~w!I^WEc1pQD(;eBVD^i_^}r9M*74gBOxEIT6RQiy%D{uubU>smxe`D#_R(pXm5 z!I%sj@wsC?$V1uUWJN+Ir16j|UNq*L;6Cjxg}du_hT@fLkwGE{7cdjt-klFwTDSf0y=(p7ESF1oe4d==?7h$4zg^|p%tz+( zsA?XWlv6CgLg$6t1^UIXp{QzmKU3Mek%$QK z2&;An!-#zEa5%^ZML#KCgQtg1U+CGyY|InaM+sHOwapzPr?@px_pfk{er(f?!Qx3! zH?FHV3n5m)`d4|?Q<0<2w%3d>aE97D()41n1_7FYrP&l)ysa&@zN@zugMqV$T z>w<<%mSFoU6nLf=WLl4kJyR!8L&Tu&K+4GIBNHW2{J@4b_(j++JpZPYxYX|c~%@twHSZw z^Ne~}VS7r{e%I%wo)Y#)QKl{)U4BFmvlKhpv%XL+>!*ao!1{3WrY2qDz2mKngk{J% zcjHK#xU0fquV$$O$mPtPsENdR zccN0rOXofy*lYLtsK`Bml9Xnmyx7Lucd1@%{6jYl}8cc2ZN1%g9k zopn_kF6PPJfA##lUi1}fl0kNyZlxPsYaev^*SBtrhx{Yri``jTjoM$=3>xIqisdwV zCGBUS>UY6(8Hm8L7G4MCF2;aikOF|0EfC5j*3*!D{SD1N7>%2c)-w0{ltWC)0?2xd zz?xwrRT?K`k{PSo55Nhn>W4Ki2dnke5$rT%AIo6eQIeBcf=nz^lVkUAj6KUqWwl4(ezLL1UQy?91<_lD$2w9k{V`uKkzfziwrfT>bHW*-w$= z*FH#q%=LWIGDVMOYE4!ij(c<&*K=B zpPh;b8!RkM@h*dtMi!n@8761P(RVq&@j-;A#$yE1Y}tD12(yJDg|HxU54qO46N+-h z?-)n(^FlnQZ!JUg`E7;7^c=1kn#_JGZiA%>1SVZo1s(et;^4WpPDB0NR*74$*$e0; zg{6{JYFAqih*83ZUiL<_wMOBdD$@mlWrX*dH(?e|trhMThS*(9cgJdNUFOj}Teo0l zGp?PZO{rZh^P3wt-8|D5qFfL{-aO(OJp8s0m$zn9;`TJ#-^2>;)i^C){>3Qow;+>fSr&qn9oGUSLk8QRf)~D(j7DvM4VAHzq(N8rB_!(P~A(< zLLX!tv?)w$;jZvYfhA>j*|YuMx1rc03KO-Z_WjyPla+y8$dL!j_Kd!rWS}fCLU3yq8HSK$`b@1ctYu@OyQzvSKK`~{n z9L7)$^KgIcm3|Y@o%pqAIOf*jNHEc_wvF}DCn|^mCm_nL_um($>QGKvIE6kv-xWQx z+q1@F?;IQ&8Q|aBXtX!M7y5CI^AdevRTG^NS%{u`w+8f2?{I_PsbMUidhzR3(H+I_ zsaCHE5jW6-eRmGu=BkTsW|)0mKB;#Aji@)HzPS%=3rpch6Q(OCPxi!%Lfg6 z3Q;f0WGBbMKb~lOXK`bSXVN48;4{*oTQ!>WA$X|97rBse<}r-HV4bI?wxn;?ym`Q) zemSp}1ibo}oT5Nqj1CTWDt3+~;%U6X*{B$E+?|M;UdUZYnagwYYHStX^SfVYo@-dD zNz3B3cIk%`Dr_a28F|bv_M%Ub@@^tic0x3?W&Qrmr|`Af+o8~Xh@FmDxJwo<%w+Vv zL!B3mQ_8z|bM^SstAT%|MgHOV{@d{fvRc-C7amhv1!fKlc%$trIG0QpzO3X4WFFS5 zeB($)JB0X^yi2Cyx)nSINgv4}+ho}V^t}an01p>H`Cv6JVF{8$pEmadsZ`V$Y8x-Y zBz#A;kg;vb>aka|I3$g)k-@1z5lcLLuhRRXL~fXHt(qKn$l*<({`0$9^h{!CJvuJt zD+pV{A?vy8G(}S!1!3pscMJ~@*=X|`cNJX>ailWdsGxdtau1_H8Fh8MZ*ZIz{-NQ; zmz1+PI7TBZ@+f(r8sVDB3fH*J!R9ArPhdV8FqE-t{Vh2CM=T!+A5~Jt5!2&MYn#)( zC#*klal4-gAHKoTNgDME+3&aV$8KNanxnjpx##gD71Dk8@51x*JoX0&X&}+|0>7Rn z%3ElZ4epw~^f5j(cG8(3pAe2%{CZV5_!sDC+>GRR4^~l|gH@*E zE6xe>ZQ|j!6U_5M;naz%gyq=VjN^OS;wz2#zdq>KIU319(Vo?R6|E(s2_F_f0uH-a znDhwb>({@{_pDLP%)9sqTf4dY#La;Iz^sEB0Vu9dfS)Ce4;mNb361lG*?7-|3Tora z-5};DbaH0lBe{Fe(u%9IwQ*-^x;*NxaruGS7b_g_*rh*N7CX4eo%eRMMxS?BDfv9h zkoI~r$x+qfGJ|rQMxl614SD;jek6~wz90}3w&D4 z92cw^TTu2r*`rBfZnqsodBV4DonU?FWoW^@E?(M%W z(7Zs~!Z7h3C^#Isb~b&$^sUSAWSC3x-kGW3fRS(~b?2kYX7|=s$EP4j$6a}h^q>1f zdz^3yM`}B)N0B+rPs&Gc8^$FufR#7-C4)8?=ILn*!rmWY$&nv7aP;3 z$6Y($!MnfLww-!g8JyYVn)3#6##DJC*5zbb z&C|su{1=O>P2xA5_iq}5vzvZ4NR*9ej+DI49u+rvXqKSgsi`loU1-5DWC>&Alb)zO z;vR+%H%*h0Fo6)pZ_?D|8i@Ua=AYJnK-IkW2?7(!jcxCzs9N7Ir3dZUR<@e+=0yfU zTBaXCFFqXlx??kmc%S(|%bnQUlI~Ut*}GowHBy-xyqe{6;5I!n$z4357!@f!B}Bsa zDNRdtYYVp;w`w)_f|(BbC_XWDQpZ0PndP!w-^UGl^-fBr6aZ=W+GA3{{|}cIxWV^3 z!#nOjW1H~S{%g3|aWUL{5DN+-oDbAi8SJvU8A)I?frr!6&?l=|`ELE(@HIqGdc5e8(B0JRudRu0 zd_sG2IOw6!pI*Pu1IXECe7>!T@O3TPIIgDO>FJL6BQWO0fla($PQ1vS0M3YAkXP5v zRFl^#kE=D`Ucvi4+X~gh*ssjWeu`RCqQVMEx47GXId<$VMtZ0p12;Wh6T)r$tgpNc zwC{Dkfij-O7G`B5H*d4oGk0BksTaBC&CM`7J&-D`T)*r>Nc80a#*0yGJjj$E=THH4 zmg2|#qIS5d#{rqnPkLtSrQBus0Acw;Pg5_m?j3y9m-GCuTW+4>(_We8+%KT}DijN* z?0jDo+FF9Dj(GmMA&{rB9z(ceRtG#SE!pDOtpn$4(I38~$EPmqEnfAaux$L!%4yRY z%EIsVt~7wjr~Kln^|ZlpCQZM`z9M1`DTqw1f^(^0ZoIm222L0g~Elq8h| zxEd&aGSny+CQ!>(Qfo%HVHj0iPd&kRA|v{KMf!i@M=0<_a0iA8bCN#e+ZB`#GF%s$ z=lCl#-@{Yg7`^g~{&K1WCJm|JkElH#PX^Pec6+Jm3K#Ns(yY$j^9<~?l979Fp6Rzf zd@~}S#ZK_>i^~}$GIt>4XyhiYt%c&e1LKS6rm^sZSS zQ+o^&{fRXXCNQbd+;?=0Se;FlhWdq6x>S z7Q(mvB#_(`)fbuwuhycE*X($yia!BkUUM`!Zd&|R*A5|&eM%W?vm`Xuw26;o0GDaw z{QZcxN5U`=8w+T}@CA+pi!>fnGCJc9+Rbl_!j8d6-^q*3uSNvafqVs-~! z>f3DeTDGlk!}3Y0lC7{hqQA^zZ$PVieRWngLbp0Bz7ih>H|3+iB#Oz@h&|%2u3}+K zIK=AvEvSo>#~%z>hI7^{CmSo_Sy&rwyB;b~Uisvtn%C};m7sq_lW0Ct({6{>;8g6; zj{BflnxQ8~;O6={z%}Y}=7MVu!8YHr)eMZE7Dpeh@hhT)qMV{Q<~fC`IZ?<9bs@MW zNjQuc0@;~qcIM|7ZxEm)p3AE?U-d<;y(#?xBaaH*$Auh8H4`RetzU>xp*vkZPqo)g z#tWXCSw&?ft#95L|A=-*u;V4&*ZZc(*1+16OxE&17{G5iK7uu?)`cq%oVV-pQe}Y_ zg!nw?p~*ZuCUl@vjZg>=C!zhoK=UVX?b2S_XQ{^3J>pG3&)^|?_Y8}L6rs)jdZLH@ z0gw_j+Y(f}?z;nTR4Jh~p^!1Go5H56)}G8-a|ecMoA|?WM1X3kNlqbQuyYVXw~#I- za}Z@d`Rp$7at`ltlk5(;$({XcqHfi1pRY}Uuly!Tq}pnvz-??mI{5(fWw(6;CfEo} zrIH!S#i#LC>C@8S%+W~t?Fb?qGlh;lta!m4^*W;~@HBGl)S$G*>8ijwHfC}LQ2!*c zH*pYkvTHBM*2ap-+I3z7^V-hckHQ3Wm!;vYcGFmPh?L~9j+s~fa`s8{>gVf zgwXwaeb;jH$2865E}VXGV94HGMnq}iXHU6kS}daa{gHcfw(G(3`1wNU`*iQI-o}$v za0^%C^Qfw)N1mr*Ki4lG!hZ6z_JR_cTvyYUx8H$6ViqcE&0>MpjDN+2{b)FCYvaZ3 zCw{mcnNL@FTjJ+a#i{5%>-k!Om9Q#n&!H+}L{)_OE7EgbWhDs&M^cp+{3D|1iEz6 z`)iT4ClTao!@aOQm-;<_+vH0)Z99KI{LxtK^ri8ksRS6KQnh6>jE;|l&&4wj&%c`uiMMrbp4%kJ~P?JMEZ9x-rb zw(XHvbWYAdYDss=WJ6_4Y3>B5lm#W$O$RwU@S>&UScEB~fW42XjffB&K^YhZmmS;a z-&9so7h-lhY_GUALp7ec=*jd-kFPD=#8~i%rRm)HJQw2<6`|@=xd57PpJ2x$j!$eL!T-16~1yb;TmM^zrdiV4pY3@Rgt6B@~-Z! zES)M)sx}>FM~B_Eolv)NAhPL4a3skmi;YgW>lhbYef89=iOB~9Ik0g1vAOK_o^-xz zf9$Q0-yN5-+oDbGpRzVuL)S(NS?q0}a7QH_JdJ&6!VUEIAR~-yH%D7$D>2;ni}X~~ zN-O*_GvL#JG~<5D9zpC>D4i3Sy}Ebpb3iXRLMO4c>LU*hIumT1xScsqt1L1xO=kp= zeuLQLL3r&N(GWOxZumH(5P(%0pxf!jQSTGcBdy)b ztUtlU{&l!k`I5EHlS*AOG+0p!gSh-b+T%mi1=dRL6>c7%WGH$UPbyqb*@ zl+eO>P53=dROdbUG~;h*`R=YX;$n5_lNpCoyU!X9UP&K6o(og1zqJ0e6QrOuT`T@9 zEXc$@?u^4&$=Qxcmo=fdpe?DKJslX9qjKnLK?tJDi;$nGzyMrg&p=Ddve-H)pr>80nCEY;HZZy3K*KS66eta2mz6=&F zsOq88HMWE1#zlCOECY~?Ix|}m|Bi8g05pO{(bYCVpbvSiTTkU=d5jzO8mPYnsVHN2 zR`N;?1C#y9`EAJ3>181Xm5|5F0g^tNt^UB!D8`Ou_LK0pZL2`w4eLLC8O8`}D%d>d zzdXnU>p}47Uv*P7=ya596q0B+7_0Mm+hG_%YmhN-z8H?rusXL54$}@g5+w@WxpFH% z%G1CC^Tq{w8AhZAux6EyZxrl2TAKPDxF@5D^mITp`=EZ&N&{2AO+OtK&mKr~py!`c zU(GV|{jv?D5s4qWxpu;TQETx6N%G-@=lwaG)Ip|S=`&?ko=*Outpz(soyk+aSAIF` zc%q==*jdkHq1@_~j?VVSIu0kEucUW2o(A=}7j#+21RkC>f{aG&YYpXg!{vOvpQG9< zmlG@c2pV$5C9KE;)gXl|ID!l+RTZ`Jc0=-BRF)MB;jLR=q51w%vmXp($L0k`qIOSHLT=UJR${n~cf4roMx$$+sYf3h9WbqAnBRlDBp=^O z@W|X9>*i|NAWUlPGT@}|XxPw<*n+c|01=Gsg67Z<%D6q^Jx&=LA;hiyt;u(~f=3kN z5y>@S&H3@`M4%Tb`e|Br_P7oufp=2yw~V??fbfSh6OZ_8_P6gk1ImP>!}4h{G3{?J zmcMxQV`U2*l(^Y@lB`1YsIwm;Co3Kdzf}qWVefK;MiZ4oPgv0S#183mDbQ*4u~nq5 zQU7jS>=;^9_~I3&snP|e+_7#F0@(hlL)-(wq-D4=<4HoEGIKXY=UGJSZdZyi-VKX3 zGKrl25jS`3y&FkxFq=ZZEsPSm%mDf&Tkn}ohMcXOq}W{dS0(JAe%EKLQ28VoEM4T`R3H||4f{J^{&@lx4zyUabv zjh21!fnh#IIs|Da{3hE~!FoPYEQkY>Tn=IWmaj3Q)x7hk;VWSk1lN^>e4MA}BFoF?Iy_S(0nX$OQ&BkdB} zb8WjFr~P%~pQo+7GF2-%j!5%2Lf@KD)T{^k?4ANt*HRU0;se965~QA4oAx0l0f@YM z?Hiv6|0r@^vL^1YEaU``jTWDAExJsjZfB{{31xZEHujtLbE(FzzdS$VK&PiJ2`U$8 zeGpatG!Df5VkKh1^|^^3X(Z^p$Q5O3Y=7lZ;wsi~drui>cap<4%?8kqmoSEVp(Sc3 zG}%6u{v0_9s$A+LzoonWmq}{$+al)&CytH%OzZG~fyw8=o0*(f!7wP5gjmjV^4>$; zbH@#SFj?BPyXM(%=WQQ-fAGHIre4(wEE269yCt1|H3d1E9_Fa(~o*Gk| zcwbg!wdGaJWegd{2P?6F=Koj~pY$=k$if4Q?ec2gdayW{-SW#HiHujj|GmEhXdwxb zY8AnpLpBsf4;P=g8)04vht`})=dpy|w`;(E3Ez988$DXfd>4c+5g<$DE!o(;SGK& zH$^M(#`0sI*70n;!rxbmAYeAnV(snX=fL{Ktc9P&-vKrlkQWKrh@k%1Os?*gKvpUn zT3-I{;-y0U;k_w8pAOyeP68`eQ_8AWo!xfKFWT|P+)ekn1GUOK(gq@~??Wel=*kMb zc>}sL?P}-`{?5BTw{+jRNK2@0a4t_u+;yk;;PKzKpZan8aT$YWkz>=DYsa)>XB3PV zTjf37a1C=EkDt#cVP6|6HH+37hl|G#IclJ! zrEfSXGTz8Zn)r&ePkdQi4ayc7_`6f#q92Z+N2Sl;FZ8~^i7#p1mD8ky(-_}PS*)y* zYN7=_T9?m+5=tgnl)=o2C;UuQ=yoKocEveLe3c3dpTdPVlfNekGh3roT@KEt>DTNR zS=Z5Jvp7}mrs~!(vY2Tti5Jb9p8WD*aq|w|>%jQ&E~Y8Co&6P4Z+-}w8`W93u+(oa zt{y$=X51B#)>=?CR4XjbDa0#qXEu|@awllO;@rBJwB5b;w6Nl1lDqcxv+ijMtUV!b zob3_s;x@5L?k*;jU)_)^?qfB=RNuXVH7^TJHg(j^gATk`;yE|`(^qd~-KaPYd7aX! z8sHHVk$++Fa{4dh@Un>g&CA~GQR2OGd9Gql8&@dbN2#{o2d-ZK_+tp6*L)LespI;X z2)BaM3VELVWqoPxu6Y~5<#(47DqDTClz2;Cuc4U39R7H#W*G6T61ePEbgZ9!&^9Jw ziTy2i?X>ic8&^ueOGgZxv)HJoz#HEsf3NAUWGU*-Ba%$DSV+)0IF}-s8K&~0=0UIP z{e7VATTF!RFW^ystn-yB54q5mS_gVk^TcyQ7}Sic+PIn8{%{y=(o7Yv9LDI*_zq)Y zMy0Vcr225e1(Rk6s%RXO@V3L4Q0ZT!vE+5b_sTp}U4Cy_tfF4|W|ub@hjRYcfdZcM~lt`&h!`QNGrPq=M>m& zou30Z1?P(7ke(tRhnL(YOWsT+8W9-Y!tg_p_nATO4SzM}`&MDhC%?4j^ita!vfk*Z zh+(B>_bccnhQgoz9d|$;o#kK@zG&>6ml*7Dt<)u3`#sjHzqBrX36ACX@&V$i)+Dx znLaeEy3;F7KA}+8g-7qK?wCCzNX34YO+U;jq$jQb)Oh3cY$`Z?C&he8-fuh@LMu-A zELJr5sVv4FZgS9`Y1^$9YM8;^>k-=CTMGKM&RGy1#fZW;HQcB{-$8>YN}C2_!E(leztTY)(f0e9Tn&apNHkRYB_r566fV4|P}~5+ z86!SEed{jko62;j#rOBz2o$=@p5m`6pF_;zAu%GN2CL-SKW*`42+Pv;6k+4p;Z+E< zbVbrI(lURmCmNAl8|2zTbcZKphVjEHxp!=#$oQGyY9%oeZpmx))#Z|C;xAwu_gCvv zs@+}F5#ZhbF8fmGK4fxay+orp{$Y%$b#NsrmV-({%LigFkNOfnxh#waV zu>W={+?A0%NU!!cw{F{aH6DLw#`{Z{r`!w~cO;xcZ9mn@dnANG$yiR%rcgmp^IzQ)* zrTNQ#2_N50sZP=Pr^R#jHw&R@!*-btEBhp;x=PkX*lI=if3z_PI)Hm6D8cu9gnGr| zbCR%Z0}hM;$y1u#B*BW_7Nz%kcFQ6fgiz>Hq(yHR&ejUFU|4&^mH6O@V;my1&*J`FMV}&m{4`B^24K-;dn1)<2ZYG#V00ZDB z^XoV;rl{_%2Nh^vFp%|6Dn8U;;k8T>nK|m*UbDcV`fivUw3$*Du22D|1=Jm=t}@Ux z?Cm%VnioI251cld4S&6L7tp3E;8FjgO%Gow8L!O;s#ptL{kza@*I)^w&z1Trs=EXn zE_drK2%vqgy_YALSkpVi;g#Mxk6NkEodo*sggMc7Oqj$8daP%PcI8DPgR9V$UuPpi zOsv%z^q3mrWKj)q=-u40ayDy-$@>^fRlSg>P{!NDLa1Tog(oN}^ZSsIp0nxEIdX{+ zrPaUDm5|Bmm-|^_HzR>k3)!1|a1U7A-;a_w3Si)d2g!T&NT|@~NcG-O+JH-?sfJ%q z$O!>?D=Kty&2ZK1qROJ9j^>zFvQtiqe0Ew6heIr>6UxIUA8A0VGG3$$T79tGyx!5^ z1M;QUXMNUF#U<5DL2F*`H%qQvY#P*R=#CO_MJ!Z&bb6UDL5s!hSzoGjboOm2;|CQ| zXIL6;m!wufwizvcK88=jwW4G`<=n>Ftt`3Z572#vfAk z%_C2A+y6sHb=ilD1frL~BdROhTFnT4F6H)v(+N!$(!m;TNmzp&l0#u{8JRUYN3zcK|KboDif z;4-;x&=N34sP8#SHqWvPmBtlB#5EsiE^~$Va5VMuNZc|SyHgnKKZLQ)x^yD+F+3J~ zz9q-}W4EYa5OY@5rb?9;JL`_+SSwJ{EwuN^KZT^m(qsd@`4oviiA|0nKE$Vy#jXFz z5mv0i%g#x+xnC9-O*Dt_>*wjG*l!I`J=0R(-t~eBC$J!$MFnLrIeQ107bEO-NNvsI zvKjT_$L1d+_BGQ9Em%%`0KK*>(jpl{cbDbK`GDc%eXX|$RRiog6|#rx2{0n*KgfX$ zpGG`xaRIAbdHsPrME3a$1m~VB*-N0l=S3RCMd7%BZ5XKbp9t&Xztf)Sxl9?>!YF!gm zcg-7Sz8T`?!S56Kn362p*#nwFGjLu^Pi3B~i?3oRc_}D-@TH(7e=4x>UT&KFE^{C8 z`9Be|p;Cz_RbXZJ^iHf9C0gRiP>cgmGsNfF9%dJ2#O)}XhaO#+H12#v@+AoCoIU}V zI7A1&rzJ0^3W+B=kXvgW2}?c+J9!(6A_Knoq#>@^b(ebjlylx)hWSHS$Os?=o@5AI znxA^tU6x+9oosa*5V4h;_OBLDU>ZJK(#^eIpgKLXj@(Jdm&DvKfqtjpkA$o`;X!0> z2<>mfWi=b3`}mfsWmzxsN?Uzgxp~8*c1knJ!lZ??N&vuq)5{sF6MuOpEb$C~jOv;u zEm~{tC!|8Emv5CQAbh8p8-|^AzLAa$sO@?)To5(*QJd@m*S<3enVQ&+^CK#ol(8B*NyD8ms6vrXO~m}wF9|E{ib&GtrE9^Ki;Ij z@YRlx2hRDC0X}J|i&v}?4|@F$+!oQ3737(Ho_3!GYx}oL&p!720~`6BR>B|3W_ZI+k9k>DUF;QN78bNFEt@y$9#M+j*c*BJ;FZ!#CzZhy4eV9f!ZI#i|XR zp0faxBjjwkQmiUe1#};$#fpZh_*gDhSmi-MSL;tVs3Wyhc>F*(Bh@jUHv@k^4qEB5 z^MrPx5SGW1PpJTI-Rr3JuHkF5h7U)W8{-wmX51{ai>Xn<@U`-KHQQ*=>YJ@k)Q(Q2 z-)K9!s8kQt{s|!yOpWus(o(;fA-gvIf&KJOE9CH%c&9-}|0PRSELy~is`r=if#NK8 z*FB3~f+uc^_;zudjzKcI44O}T18zV3i4N6squL{5B67iWt|ixR{)uLP3<+>Ek=k&l0=6kpwYTE7+}*mkazU zwNVOxpjbF59LY3jH8-f1>oe3ha@Afh5;Zj_4KLhoA1iX?!)xc^b`*3oAW`H#fb#!M zBG~^jKRJ!RJ8)LIx$L#pXgZL`wTtq&#KP69A!-uLVD&a`MgS{K1f=J-eyk`bD{>Da z95-}lXPpP$0vMug-`Mb}Hz3higIJJ-T^N&)Na18xlNPG@JDNM3Vd<#C8;z(JfA7&A zBT54d9|s&jmr_h&)@KnPbahmtJw|Kay1TN27rFe0Ac(N#cKwAI3nEyjN;~25lWrON{F!ayN+$}yEIIGBD zxDv%(2FePwRe1W<({%yB?qkm!lFrWzi(t5k?zhwP!}!>2OMDDyso4%AKL2)Z{sdAl zOq+2t_mD~oDq0`7?e~O}4dVGB42BOlZYSWl8B$$1fmRHDVmpFgFw`Guusq&JEa{5+ z##v7eoE_g>X1+@Ap2B;;SloYQtf;m#xlw(yo6GlVZv=cr`cL@kxZQJ=AX?NwVYu5O zTYYPL`XAY9mvyq~2VK>hw4ob|EDmP!{WFXIdm;Z907k1! zD*l_Tf~;=UXOyYiYH}6#0tSM*R}*0juSI=l4CS7?FWhIN2}u8tFV^+Q6&rJw9)bd$ zwIg>~+nJaM?;jSaehbV){!d`;WBE>(I+`n)5@7^U0pu#&BaQa`b213U_ zYyJT{_B?eq3K*r@;L;&rnc5Z?RB&Z(P6l;JaUjM1uA7%)mXN&Q)MGEs96o%`?GC=Q{xfytE zIMZ$MNLLz`>dl}}e}k_eFx3GBz4h0Ax|8yf1pwO&tRN2-A>Z&HGOYY}83w4&8-%eJ zk9yMId0`Rw#rifl5DNswAf9EQISlhxEp9Jjds6Xv%tMTiLpjBhBk<;Sae*&m#&;QFW@g+tyeo|ZY z{_x=-bH{jv79et}FTkPPn6#4@#bsxq^bi~I*(gA!WdcB3i^v07aI`U$i;ku#*4a42$7KVxS|>}(oX~%5 z@t-jN(SM-SpMHYHL;Ej+|B2oI!-(+BWfF`QqU2HFykG$ zlFee^)M-|&99|l(#Uezo9!Z`^#&QTPsvW~HdAA3CRDm1#5D`B8#NG9T+9FHedI605 z#gM{1;Y@>gVezyU-xG2h#NQ1|Z@&FgDR1POy;kMT)FJ>;xnV$CJBDNs<7eN_!asIM zGdq_&(fKA@wU_@PTmNwGYzu+?C8B?Nhk&Ht|4Y*U^w>?vIoEW2fzJ&qUXnre>erd{jAgeKm7C64}Wx)Te3vc*Gb?5 zY~tTP?B||6MD_j61QS%~^v*wi=?Fb9;KaRgr%2BE*Q}Qf)+*EyUKzu5g>Tv)|5bRB((`Nj@dOp31y(q~ExQ%#YHT$B)ix$d!S+^g zD;6^`*A_{~W^2jMZIl>5jD_zT-w03O5{>h>jiG(UCx13iIc~a1`*mxNr*TY((?QAg?l91VAUyNCXdDwomj;L}*J91xi68;6!s7yBH zXdEnXoIgDt(zdb_MRv`x2hr&6GJ+z}fLEG|3cYMOj_`WE`?-WE=C5#H0m zJbB;jFj5JHG`6dr%`_P7@lQoq%L9xbVWP-J@}uN%eg)TJ1L+}#f)m%;H7KqeTHln^7_z2;_PnG6l?I)o z&oG5F@m%4Wa7m_heL0_2TD=7k=eNF3^(r%o^2l|O#W{wO z{Igau7Z&bJJDU@@7MeC01rXa&gn2|=_HWy~tvE)_)c52ZQ8yxE6?@3Hj!NDTPq2W* zGwiZ#+V&K8i4Qlu=tl~_3^P?M$wuL!&Es!NTA10Z72lXF#V3u-emik@Yt@kG z3OaHMvARm=>F|U5wO@XaA3>KLItGYd4<-L9AjlNObyEnMOy(u@ zWOn1RiI=gFzD~~$ojPjAi z%#|J)JQJF|;3nZw$y(YHLI0qBksJ;Wbr3KuCH`Y48pg)u%DFk3yDpVmXq$=<&AKS+=Zrpw0}!#$^-c%c%WJp8I5*K45!7>M& zmNpt*RnSUmH3@F!*A!nVfigFM`N^(;PeW`c>GLIkd@W-E6Hxdgh=VM!9D@wK@8l{p z&w$*xM9rBgKS=7ILXnNbpHK$UO3~^5aP^i99m4tG*>b)jwUCoPAx*}QkcB5kiL{5? zaw|%%E-9lTm-73Gqqr*lgMIN=PVpH;dhT-#78Sd&lj}1$pWbPPvW?BI zqS4QC(eVy@haDU{w-he0?~rXlCcy@7GnOn2KEWTgDIM~3=&$EFlsxk~g>>n=R zv+qLR6B*jaobOaZm<%AM=;`Li{uxRr@)@PMd?8&Kw`-TZiAo&Z#QzdI*k5aaMo&d- zb~Yj7(fhR|t`UgFkwDI5tZi&?Pso>gRi$Hz2cBa!-$7%^)xwj;A$km=8vdzSUzkDY zujgx^m!=n*mhs>lZ~?vns7+>qsP4@9?4yd$FZXR8K)h0Et}PCq2`fm z(q3wLjmuqgGVK$K(fPh<_%cY8j_B@?;E7E6%d@$CT_cm9r!id$X)b)snO3jaZe47< zD4*Tx$xg;lM4f6qM&9^a{h;g6HeI{S7}0DjW0?DZFwfuC;M+7qEuvSnq}mr0P|JS7 zeIJSw|7^^&neowI=tml1`$Tl4#Sd8+zDsE4HB<8{?mbc3gG#(VdLqr-Pg)liKPt@2 zKn-6sUf|E>MsK&eQqa2+R(}58tYx-(+1ZB4&(B!Buf}QL6Ny@RcxLLuvrr~S!$0^Q zGRGLbNBpvn@jleJEZh0l8X+g-ib#7OLZJ4l(+o$}&cd+I7^fi&Eo&NeQpS^ilCHTh z!L;T=6!MgdaY-vAsBKTDf13UtyqUNkNe}3A5|v;@(gYDk zXOzRirxDQNLR&QdXJdm=e&V*|{E%h4#>?<=mIC?Qctb5W0dG4RNbMgK401nh zl;g`HpRdJv{SrRdJE+#vi=G%R(Ye2yBAE_ju*n{K#9~7K22y}+pjYk44N|dSfw2oW zVHXxFhJqta8AtS=@qxxunfyel8CjaXvk+I6t=TanU-^RY2bbv|#ZSL~8z9fQo1-GD z_abi$#T_ISL{4 zsN}*tXLkMoJd-=HjwhWW=4pj7f|2EN#Rl-2c1)Gl_sGm22wi3Tux328Og37B)Rf5j z=FPCfm`Az8&Q^)<(|yypzwfz8bZ{#UHE+hkvsL>v!M46|C$;+e!3AU&iHbzdX(eq` zA))n5nyVn4zm3-*iFP!@W-o^wNaOJR8TZI$dxBX#{;^T|_64`$vQY{5h`+hIb`!Ta zvwCP#)#>@Gf`!_4uMCL|-W|>%k}*G43ogx+4rb1O%@@z6YO)MlEBkk;${n|HtPE3Qpfq9z-CVXeWcvg&3y#~-2*rj z=T~*q=u?rov-rWM>Md~=k#L4hpS(Xk7l<-dy#{w)26?P zr6I|~Ekw{is>V-nFee@xaSe+^Y_LgY3t71VbBtM8O5<=>uTUAw#mw0V0x`V?*kg%b zz=pSuzx~GLCRM(9zWz81zuO@iU1pmzY#Ns)T_R&8<0DuQ?fr;;%mYTAe`QUisix3&pMhWYAF9(+N z%sPqd{wFj7PV0Z*iCN{`|8Eh;x8?jV0v`ahs5)A|C#d|M+)@azr4firzqlvg_uV12 zGPNapHOs8u?RAM=^5#mPp!UMIjfmYoaCFmk?>?I)Z?5(oTv`+W`R?7Tz+Q!WC5u=| zJLS5j=aLtJW=r1{2KFv*t_xYUB=5a1bZ^%;tmXKf-@~P8?P2+$1i%0pvBOek1snny)PfLn?Dl-Et%HWR+^v^Sf`wHG&;aMob6scvj#=roh_^2Bt0ln0t zLFw?_B}o0DgZ(ho6YnyeIa_7LNy{Dw&dlCUReV!%px>rE>l`ANb0Sr^txV@lpmphonw>P1idlMC*mynP~4h9u3X0D$>mKBr0+=!okUjHb@ZeUGCdbJ zAB$ThpU2BL#%o(>xMKL7wJ3#@N5j3NEaP&`RK-uRz3>gSz6&3UrIB0p)hXtCmxf)* zS5+|d)>H3Bqj{wp`84`yCM)Ph=YdI7+N{DIRc-T)q?tJX=*1+Z!4kTwrtD;(1U`Ic zXVwR@{5E|{5msM~94qQ7Bdr%q^=pzuAN^TO+7jBwnaQAFt-d(gimw!3=)Hl1n2TSq zH3_Nr{v=6`PP+n8SzR)|lTs8#R)NSbhRavbV-!~6bj>y4qCE9zMZK4EgP(V2Njt<; z*RaW`CE+r@KhW)xIi%W< z_7TxTZnm+njQxUBATeh^;SuO*;n4` z_MUF{wUcO%PL?rSaNR->9Ho&{y}w76`7=opg?P3o>OCI5a2ZQ_H|tC@-iN(<#@_7c zUFNW@Rxtkne?BC|qf4Q#q=%Yes)9V|W1^y`pFYA)t>kW(I~!tj@6oQzSKb-!8RzUI zGwkq5><@vkPnPmt(w7i-r`d&T?|VtP?0pnpraAoJrNS4zb0ZkXTO(4}cE9#Kp>4w+ zA!^iliu{=EyRb+?|8`~Go8>KXvl5$_UiolqG(nW#TUYP3AlN$iVzP(h7jbd=X3^js zvjRm2*#$u%LG)-E43Np3zQa}0u8?P@&!(=g(U&yIMR%s-k{a?(I}?AUY2II0FPnb< z1Usyz8lyonAwn;X;D{Ne3kwV0R29EVq8;S)xax$ZEDvjngh)bElV=umLtvW3;R0p) zC57s2`g*#Rn!?8tpy(7wjTF@g6b(Oz@lREhwCeRDt-5m^~ZS2NHeiFX2(iSl6jPTpQtFb52?Yo8ev<51d7tsH|LY{_zU>b=?Zc7*GI)np-H_!#*e`D{>qnbSTwozJJX}1EkwoVLbi*=UZ#2_JQ zw_B-2WILiVM2d)t5KtL2)t3rYgwz3oBBX9qM3e}~AVVG@K$HX`GK4V!Vu+AHCNfXo z9n?;{ea|}QtaZNkJ8S>rTI%yWd7k@s-}i60uj~3jPSM52G@PnI)L4>N+ZZk&rl*ye zx#lnxPd}W0tDKtu!SYsp;XRHWhGMhaG*u(@Eh;4*?$0_N>nu0LOs4Ij`^1OIMw&jw z6AHSNtwh7N2!nm|=(eMYDSOR#P~4|ow9qK|O*{Mw2e0^((yB|EGP4Y2Vhm&WZt`uj zb4Z(P6n)CxrdRe}s7&W@Uwmn_`FNh?s4KyCdjX-0^(qMCM+W?ECCfNQ$N zWe@PS%>wtdfvo=UsrdH~Jn8~Vt6>!2uvQ|ZPiE~Q-mP}YcMBmmjmc)UlxnuL$QD28 zF^C@D!K2G;@7O8a0j(rv;;<&&tnnS0uTO{aHG|glEXoqx6{V^{dLCWtGH6bg1spi4 zSTa^{hfFY`F1(BsOLlR5!{wEZ1MWqYwF)rly3<*Qo6)n5FSMypx|KW>@pm zwXnI68eQT*;2&I~Z>ew?H!1R6RZ$5iUYV!J^fZDfp>dKzYj5VE(Io#KeQvW0M3>XBV;j_IZx?yl8!fU8=WD!cTs+>+!=4qkpSMF7wW9y6AuwnhRL1&Avl!%@O(ws4jii9)FvV7r}8M2@lqeOu%Y} ziFJ6*kJ>Bf+LeZOI0PpSKhYCJHBy1ZHiR3O!@i*zENR7m-lzTtv~RFV-c%TWj;E(Y z8uM-3dJt*a(y)$Fe*Wm9l}_}R-CQ>mB#)cVfcki-PuazZcz$faQ88`;hBnErQhm+e zi<1wT`NJ%k_<#o_UIwv`)ktpFIn;(M2*XeegxmbsQ?tNC*p|a{Mb}1)a03C@;88+~ ze~W0KLF6N;A_Q+ij5`Xw1tf zo!m|l0nIBJNDB0jHARi2z^Jy#=P^M%Q%jTk{b!gvXwQJ!@Lu}xUtqh;JQYlJ*;Vh>RkqTQba~@ z$qswQt@HMjhU3=OpKfil{~kh;{FJF4 zv^C+*m?Ph7XZAMZ$58AA&f4=B@d=Js7-v_C=wXNZ=_}Ta8Jyd@l$m9Qnu>TMxn};_ zSVu%Um?4#D;!f?d&t;y<$HC8_*u^0&mMK!qb8CjJL4t-Y8cRqLk|fA#@U2Z(`{Dqi zjm0B`pbi@zVDPKW6^A3&gB?B*-9#OfXGl-rv_*QlAA}3mY%_UpcjzE~Y0#x%?3TAy z71=1LPTq@l&UNY_jCR82l8v!4qo3M`h58sN3k*md$agY$Z=OCc6~U_42Wct&l=ZOe zX3Nyz-*2U)F`6Ft%l1qr9v9as!U|hUIm43XflQbr17^)3z0V-kGQ*%!zBJB_%CC)P zVEtz8HlDiB;*)m(NL&Qmh}Y=OhYe_SGRew&FuF$Vc3e?&!|Kj8FhPQc$*Vh`VQj5Gc1LR8@fSQ&LUsa7V1382$Mdcw&)OJlOuaLi>e2ty ze(_;s4}vAMW~7L&jKsCQbdQ%!hgnxvh;EmPT6ONh*IGm`?k4MWaiZQN8`~-3CNF9x z=PaJZ*OeJ{8C}=4%b%_lP}|a-btN(S;a$?l{jR97+N!kRly!KWD_Z+0 z-mFqLPNtpUy;E=ehbEn;x%NGN%dxdc% zj1fAYL2R4FOzzL&58u@)ay5jTgvHBU6ph1?8xw^{nRo9FoLzZ+zD8UuHknH`n6fSDEW2=6`6i z4A#d+nX^gp7@cHVd_KnPLkORqR?E%^h>8JoT(w+{vGd=dHJ*RH=3T69v^HBOzgkYL z)!FzPXBVr~I{k#4w)&p?#whouj&0nhR*F(pDB;XUUYipi5X0O(Tz76n_z83_arJ$P z!Atg0SBp59Fit@;V+k}5XYP#~Gq95JeFWn{h(rh%>JvKq3hs^rN-U<$jjyo>aU+(`W^4LZeC%+kUG6!X!U(K(17%APWN=o7Q z!N#nGi-~ClILB!%f|$~@Mb*)vCV}WZ!rB=MyZL>u*;~wcLNxFsg# zcAS4l;*G(^Sl5U7W9}?Y$v_QPB`CD7$BAj=Cgbb^{iRhBj2N-XZ*ZIKOHRj-g!J=J z>foK_Cht#bhDvsF@7QHtYYE9Nf+(dBhZj(#4*oWHXD2w1t@A@qg__0(8nd!6XB4ZT zEi_$5B<_f@sX*XNN8~=yg0-oH)D4|%Sj}4TDsyh0oHyR73;hnnb_T4D6sFTk^gq_Az5T%Cd4kQBizG>abof|5IzcaG9Z6K ze2|~)69~3sU0h^m-mx$^g?g|AK0rkk;;uYQ9mpEZ9iJYk4t{6BgK=yQ96#=>#m~j( z0UF~JkIquvM{lA_eD4@HKgbS6>Iq|I=EQ+lY3Y2mJ1A=IFl6B*=};{}sy3`t6CY^e zLS=E#sjyMPyaRt%*pH?2e;#2LI-C|@P#(+fQ8>N4`HX)RZ~{o`6O6-g^I^V#IVM5VyFlt}_a)RIR>e#E&BGQK^Q< z1mc#q-pS(|1z};6Jw~^BnP|T`;i?-UFv#Gwljg@X1}JE6{p#NVbKX48p-1`8HEsR~ zy0nJK=s)i-`5VXkfH8Z0CYDe783yQI^G7N**q#%@h@6NG9%c}JnZLdxqk{~GHMdCtfRgtxltw7nW565i)hpfSb}Mp|xkJ%|yGL#O z7QPOw)&N+Cabr!1y}2dY@LAQr;)C~HZ0gf4ovkQJcqEVzrEW?QG$A^{AqG#?1r}F? z%s9-)wi0aZWeP!F=5#Ng*QLmpud9fueRszmC~6f&Daz#;j(VJW`E>a9&?FBcPO)_r z2@-D1^s9~r?5l`=^_SM>>40s3EOlDdedVUd_%y(W@MOO3w%n=7DWOKAft#bw6lxRv`G%-Jm!mUy)gmzsup+OtAc?LY3sLmyVFyHj|~E}VRRwZ zTM?kWh?Y&#Dcd!vIU&v|j=#St)?ssEQvChtuava2@k=6#Z0ZDPm-})OHMfD%^t)-lZ&ikbfusTErcvPCX6@2MxfGQwzXwT?IH@{jWG zkGtW;yuIBoWB*w)?pB}du=hdoj_0S$-3Ux);UvdCDVO#<6lpq>U@)Elbqv`?r9>~_ zeMr%a4cm8&NN$#RRxCHPV~+5S93|c`v?%{kJy}I4l6Q_Sp4puVg+2e$%wE|hcsG}Q zXsY^1{4YhWt2I%{`pGIfsL?w)B@UkrVOM_YPZZ`Qq|RhG*cPe}41XpSwq|xu?q3wq z$nV=JzIwUyfpX;MWtLwcVYmwl2-=#uPEgOgzPrj#W_^*DEP7x-rb5O6sEt^i&~LYx z!D)sqHL)U)SImcF>yX!!*6Dn^PZ<)lYI49m5&mTTDO~NKgLMM`)H^y*g8Tx6kk>4^ zh2Xm!P_+H4U%MU+T=kb0R}HV9-c2yZFdP$J^8A}1@N*#m87_Uk#qJ!Npeom@;aHXU zL!wztgvMZNGI>=vQ6R6CXxwk0J#!X>YCUPe(U~c=v5&3r)stcKK*4f{rJQkU9gF^P zOkt1iM^w&7#Okw`5|f&k@An2>k6s?cen9C`-ezJi4}5wc*l*^$`Q^lBN!Tdf#wXL^ zL!vr?NG4L{LZV5SL{tV4KQ)bEOv{LOsG2R!0ySKwTdMT_Hc$pu!1(l?XF*kfrC!xNhYCJXRz`IjjhhQ@K<}qIn#$a?!9piEE+3ub*1D{yl!)_i!bY3HRJgQ#5+&_OV8_55L7*693;(`%=h$x)> z;W!Uk@J>HQ0?mbg-DNo_jH^m74c_tpc9N4`?dSgH)6WOom8E?$y218-vg}mvQ~O1S z33n_N;9O#-rHWi&sUqjb5A0njz)}TspKOd?Zgs#dI`{j7)wb{a z{^pGJR-M&(R)_nlquxC_viZI5_wg(37DUc~)YiP?-U=Qa|L*tU{K^k=&WS#<+Mh9i zJa8WzELduegDYmaW(<7zfBT1%0oE+>ob#_|6)&~{V3rc#)n2n?XZ~Ef1w+%0r2_Qt zuUNbXJJJvT_218WNPVrW60qC<@%7%zOaJ6rS9Pe<0UMs#q%Ksodr5Yj0h@6sre3+9 zn~R|>ZqN75O&DWclLFONC!d@jTUyOr3P;cLpsefqVPVQN0@QAuohuiXs2)m4OLIzI0r>-ItrRUDCj;z53c5}L=UOL@Hk~&R zXck~FL~`W@ERt-vsCI18&*K~60&TN?ahMFrNaTgp*{$a;JXlY9m<$O9Fi>6qgxL@W zJGR*B3=o>?SsG_`=mBAPNwL!~keX?oL3Y2zdtSd~`&DtbT~Ju}tRSEjL3qD~k49eJZ1rG2Dkfu}T@0X@2rM`L!ZG&SZT)ligmp>j z#5*N#bS-|N8sFbOVfE;c@yVwB-cL5MBC}@D-fyAEo3=ZCzrPq(-Ez;m8Yo+xvOM)I z@%SM?BtJi)oW(hywBo$c()fjc{QtX;Omq$Oe&Pp+Sx>6h08sxdQ7-_Ar_l`-axs7v zCr=bf0sH$RxL|k)w2iaK4SfIi6FKJg1X?HH2I#H$__G!&p@qy-nh3z*&EUX$b321{ zGnp683q{VhiUJG|V1A^<{5EenTyJpR!1N6f!1TocU2oBG`Guwp%&xf)%)W``TVOHH zZ%t0Im>itB&hUcXf{%f@hs%MvyWg_Geq(B!#nem2Ztt=@={IIhVFNP<0E)m2t>G=o z9GF;o5X|EfZy83vnZy6nKH_=c#1rtv_Hr*me3IpzQ$CmO20k z*9>H-=UZqzcBO1rG}r%Nz2t?3SPllJ{cKhWcbgI01N-+a2<%VFa*MaEwn91tgLwHJ+Vi-N>!Sf*thU%yMede^5*}Obykh0kdM@T*g9)$U@M-l_BRt#5YLtbg^Bx`XM;o@81dxFoIdRY5X-On^s#ZdihM`npBg+Y+%NzZT zUH$@zVn{+r(DYG^eNqL=tQhf@B>7j1%b1OpDOwplw4^d>U_m8@=TuTXdO^xn)74OOy?__^p_SFK{jkAWut_alyWZ+pSdMkF zZ-%TJu<52jz;IOAP#+0|ZeDyb>wCAgi#y#q3>jm36T!N8AR zUa;8e5l{-Mzulra0fM>Y|J?S!aY(?~$pOz+NY-MnU15=odg*E&O^4g2X)P%_Lc!WF zpKbuMLJKk-JU_M+0c;&S4g(27Aj|b1d;Slc;$^xOC=pQo@&Qn%pnuzgAfxt8ir-R);+u-yCq zbVE2+N|u;TyCkF}FSk=aXdfXVFm#-soKu~FqVik779o1u5##Nxl7)ob;x=u8Eu zCLB1SxwLd`#Gig_McaB-0)8`g`-`!^y-B%$KW8f!rzP?0mgb?}?#90#5VzzU^Ekz1 zDMp<}sZRp|GoU^LR5FimeH#t``ck*Isa>LaLb)FB?Lwb_f19pX+}jxrV?_CK;wcZ7 znZ-7+dI6KXod)m@d|an1<_7r|kQsj++x$8bYc|y+94|=K!pt(5KM+1qv%tzd;%qcR>I;}UvAG`{_9141-LbvS}ESxc#l@b=nC|k zWZC#hn)X+1K#(j0)uc}|9lhKfECSE#9mdp?0}((Q5Y#?r9QVMFp(Y>Vw9gfw_3Etv z;wt_TlqF*WElIQLmqwZ1=90f(4S+Rm?(#S8H4%V_mQu}fH7I|q@`(HjA=mXPq zceOgnb!w)f=qwHS!uPVC3cH0R3`*##|)cb;rdV<3? z8`zPV|IGtH$&J$O@aGnJ5S}C9)AUnw%+nN8r<85#L(MT8C}xEeZfb@;KuvE!eL?`# z4-dmrlHnUo2h7;t`s*@fjU|rh9;xxSU&ms+W3nbntph=4 zj<3+Lapt|S`lSyNibPMk#viF(56zdatAR5+u4U+eST$re>FHEsKUFX@Cvs=&CcZ&C zPVCvoz;3@D@PBnTiI>ieWjJazAuwT~&2;xA+UBl+;!M@$M^3j(X6-5L?0-F?`1ah}U2%se&K$zNUc;A{@QdFDcoys1Z(_|lxvgZ@JBMX+6<@)N*3m$nb0(0> zUNTe*C|bwHHh*NbfDK&LA8$=f`u^zuAvcP=Sv&v_y!`06Z?N^9orPea!GY4heeR=q zbi|XRn?!M+S-E=Q>cf_P zH&5yokDU#9U6-D5@H77BQvjz&;=Zm{H8h}giPC=Dk&6$;Cl?-mS%jG|n37Z_vBcxM8<DLF$&uHBTS?{@|SOU=v*k_ zs9i|ytyu{U1W}muX*ng?yxaU$0}IBJ`KPMQ6U)neZ%Ut}@n*jSFULLRf^9`*PrQueSU+K zuKfIw!+T6JO7leH;ndA#KbMIgWhpSYf1IL&mN^il`*GCc=zfNvQi0JL0?`yZUIlFS z-4!jp9U{f&b*7{pj}4=Gd;44bAS-`2gt%kPx5jnOor<)l43n_304&$n)A>FQBXR9c@XDrn5ZK+?LxyA!qH60ddd zqNF1$x9ED4!ZE0I|A2^Me4I{m=YYW#eI+m2V7>fXnaD$ni3AbUI1H=BtWiqt0;Pau zU|0jaDXibEwBK%8mTA$F+V(8ey@+}2dfw4f2Ph7X%Tu54mQR+GTxB2VJCde7%rAO{ z6jzz9Z4-;b<0Q{j*z5PI;?6VIU1aRRu)lXTpuk&`M+G|{WtP>`(f9*n5>kncoh;YAF0zo@(UhD5IuSjdJ-MRl8d z1(%+g@q5iSM}!+x+Dg1Zp)uUSNB4=gkGPy1>w?kA+ADdQS z%!UCtWd|}dyRZmRlcbS1=!0Dk8PI_i+!4mJ9VQzv(VBmKkNKiit`hMKZak3*$}m&ho&SMHcVPc;xPI(?2vyfwY8 zj@PD?%OV`BM>vFHj`pD&52fx|0)_BnG_{-0E3Ig9zH)Nw5@`W36wDP6k+&+S5Ik<__%Un%F!hSdTnG*##UZ_dQ zL9>0doDl3m@mH9|*Gpmw!;cuZ{x;m0$$u>{t?L!w?Y^WVzS_V! zYxOX3#?UjbW_fJeA+UZghdTXy4Y=I{h#8kYlS5h_dvxt<=lq-n{Qa8znb~Pcie|bj zl>bTiW69JlH{LpE`C{O(H=YKuK>FL!$~~O}Z4mdCeHj$f@IKw8mVj2p?(^>~FuJEQ ztAZ9p_a?aA@T(_Wi5F(hp=YlxVBUSeEaBzS=1ThKxj2My1I~H1?}Zl{M_L~A=~uFa zWg`ag$LC_8JbjIN+VC)Y_afqH`d;4iN;YSy!tbuNFVud79qUc|RcGT;9S5 zd_65PqWV}&U$Cyjhki}WduFn)0!-gkwL!dNnnfpsvX*NqG8(r_DaaxQ9JG$^U*J+> z&`Dnn8wErv4v#YHUh%6Vh0P=XGC=2i=>XT^Y}TYJpocPpdu457Njm&*3&GUtxD88M zT1S(#JT#6z7%3pth2U7vs)8@s4t`RJz8t*3j>--%)n89ImkwV8*Qe3P-ItlY9jdh# zVxA52UcSE&_Ze=gLL7EYF4qm%vBN|@bb28##~?YP-ZT>22c;Oos;6$gWPFq^l$AJA z?5H$CMD>`p%ZCe%s)%wFrRc`d1eH8$M3=TR&3z1iFdW9W3)+plD0zl#;d~6^Pel?w zt3_O3o)T}g!Q>*1XJZstAM_QTNnAXl6xV#7AFo%At5R zbc}=v*`hM$a@&^qs6^L9EqCRtIK$0zb5_%nRcd<)%j5tT;_h=lE}`*RuTH^e1lL|P zeqZ&8#i?3DSd<1aQ5bw$C~}3du|Cz#uqS*BT7iKw2#Q> z8}$enhflGF!}1eweOp7Bw_%Q;2^WqR%XoRr9!*o~bW(1-$v)U&teiA*X)9sw>cO+Q z^tOchb()($4UJq+h?>JeAv{koWCYTcQJO`& z!Mm4+lp0f|-gLf?ah<3sTmMS7p|Q(U|o2g*p7q(tSM-% z+}KvgtJm*{zrX8-5X-A@#<>s&JbKadq7$oCgfF-I?y~sHLm;ID7`yK?!r$y8LWV1) z0)?C~PQ>`AN;4??L2o_Tt}!z2Bh}8J590rW;WX?1j2Q0?d`RSGdU#E zG4Sm%y*okc7bAHVRw+nX)*co}aKa4k!fO2rEJJ2cHZb`GBfwrJnj%$17sw((SI4Sz z_UfLrNin}ao-f@OCm^=0pzk#h~Vxn#@Tjo#DmNedvNf zW@x=!r#Yt0t4ia{CgDhhLj=0>eA0CoQG3|IEcT)IM0G11>TuxHv)AtZPe>uWB&^c< z-HCnMrfW++ME!&(2%PnHg9dI)vyC0cNz2_>6X0VMOZvi<{$+|}!5QVjcR@| zuq_TBm$RKS+x1I`D?+8np7ktYm?HaG;bRiaM>+3R#@c7D6r#hzF$$wedJXR)yJT+W z)Z#AazdHiy?lH@#^zJ_9)S{sMDf1E;=SCVwIC7O3!4KzcWZ8v;XcJ<`rTn{g6Wx%V z35Qi-!lbg`IK6!zl<|O$Uh5i*%<2r$b+ihv6Eg)=hZU4)T4L_#X;w(QzWW(0BxliR zq%&4q_P||ipLeGx=0|ECqkywe=&gFB3WLMyNE1I1hVML#icp!<+(ng9Ytyu|M(#u{ zw1Jk<3-7RbQxh@!;*$gv{qQ^$9cJ}S9?_srDa3onE8~_&+=W6ar)k;H}GpK(GKxPU`(l~1{+X) zWI#D`Ni+BT^Hmw7pSf|*DqHov_R)j+_%$h1p*3mDcI8|^p8U4`y<*SQ`F=< z7i7P|IpAD+D|(;wQksGdCpbu2kw6BInlTzSS%NrKuakT9l8|>gI)~ir>vWX|W4pL< zJ|4zb8Dac*t?vBiG`FsW-Na*uH$LH&imV$eMa)770HbAiNHjVUz7Me$hoB~eqYGOf zI#Es_YjIBZ@F&OBXnW?BjGg6FWD`TZZ}Ehv5az|!9p^j0qE>&7F!Vp77A!qJ@0XgB z)sq(B1M6?i)|QoknxQQjAUSu@9LB<8uM(Br0RScjdI-%Sp-hP$$7BRpH6Yi8qwRO?aJf{LJ^ zk^M)BT$)lI)8_+g^G_JQGZ{Ky(@bF?^G6b4W?bx~aet~Yk>Eb%NYrag@!b4+=(}%* z>P43yDpal2A+*UUc@$GEi-|?XKBd;-cL614zP@>6;?za9k4~;;FQnE=X8|3~<|-0k zcn74h>$8pauUuJ-!rQ!fJiQuuGJ!rb`PLtkz=&N*N!O!68wT@)olVo{wGP9DM(yPo z<#58Ih0gf+gUy_7r)I9{1I_)0r!ez_Y)I{$RC9kql0r%R0S9`bnN1pvo1{k581waL z!Yi|$csbaXdLv)HpPjVuk6Di0Mh3CVfl~LDCT1YZWSB`D|9cbojnUDoAurmI4R|{ zlAXfYXDvTY3*a)oTzHPzdJ~Ca zx4Obm6yNwC*o;!V6qz7dMPOr*CLur3(2&|NkYTJZ8oeY5MD@G1F5G0JDI$|Hreb?T z$e~~}|4vLhJuTOySV>x4idzew`^>`O^zwNVeH3c-Iz&HktM~gET*S)=vH;7=3eM&` zV?le{Bwgv~ark3Ikh=k|l1&rXbwCL0ZDD$$)x*-6Z18KE7!<$MjE-d2y8&i|Dn9l| z9fEi@33pG^;mlnvXEzk*za{Eo1<&frqF z+2s0_Y=sVYi?aFRnh{sZr;IU!qBmhn?{&jFDJ#R0RdI{z{gfS}%Bu00kUmN+X%fHF z9#x`Ig0=%p^PxCr^~XLc>b#nZN(~q;z_^ zoBg@1!fPtg`^Mu9-Ykf~$ZXOEr0Q%WC4daaZYd;_W*H_!eGGYe?Pt)2LD?&%7SP*L z@awKio-(El0kh^>>-)8~JISbziQ?0XsJNx30{4^l-d{lSNOn0R@?46lw6Gx6IVyYm|Ov+$G5N2L z+MRnXkD!q?&rAL=RjU)0R%j5*C}p&htvSf*x;_4jQ6@LX_TtSy3(4c{F&*c~w<-Tc znBeg#t0|1$Md-R{%~fRe8qcT1I zVxEs_FF3_|RalR(ZIKCLe{w=N8l?!kjfn4%G=v_o5CeFX8t-YZXu!hhps*NDGWzTW3 z;RxWQ!Xi`_KKw42G!2~b>EUp{=Gc0<*DL-3CnD9@TQGPf48LDR;O5rz*jc1@^V!Kh zMjqaH!oLu8Qa$xh&$`yY*yD*eAoxk3@8RV~S6>GL?^t~w4#fIr>IJz8IaK6rtoD&K zt5ZzkCkQrb_w+G1pVIZ&BfKz~!374RmshQYUBmA4)Nt74oIQPZTnw(3S@O4l;7SYi z8#@~2ahkE&R)J}m_gKDHqTM45;QBj6rTLHN$Mp>-+#uB(*8@`!9I|`@$&kdG7A^I> z2$j^GZ0$%mwS!morPt)`6sq8`1B{qEp^x576-%^>P}Os(t?h8r^Oj))2o=a_#nhUU z8qvokHTCP|V-&tdh?4D9`O$IOng)hPJWZ=_qtTSHh<%+&JCd}`3vEJ7T8|dnkPtUF zRs_sPu<`|CC&f;g!ZzMxlV*38NG@{Zws-E5YqGJR*}Z zUdia@kMb9dDcJh!(h_mmd7)x}l84(!IBD1=ihbD5rMV3=I_pG0&H>D;GTcQ{7(Vu( z4LYAfOT21q4(KM5ur;G~*67^xJfjmDrKy*uFr8KTqS<`B!(=)2piG-Z>cw~%xw(zl z)nrkxq@3L@q=@Uh>rT}e`B_V&PQKp0!DeyoO(myq%mLI@4mGr-8k~R?`6)uO-0>K2N%DJd z4uig?-A^v`nP|5IAV+Xj(F4n-2ZTKc@MH@ePoTaHDoSt8^k0|9ECr|+_ustG#3D2i zCd2O9etGN-3KE3I0E%IG*6aEfpnhwO5uQ0WJWns98l3iCzLoSE&jEjp=de6(rk(|U z6~->!+{BQ$`%{qK`wgZ&;M!l`6JS4ndo4OsE>K_VmTdaXFwWpgeyvvB1Kk+(Ecq^( zKus>)Q@GP6orn4M@j&gO-I3#q?eSYe|Ow&&#zxWcew z*CHB0hnL2;-MZeeyg-w<5A>?Z+&9e$n1LYO-3`PS2$GdxxZj?=eN8(F5&>D=Oug-w zYmnjfOSg;OfKDvAMVl*&%t@O062a@^v|rIPm;dmU>wg15{o~;O20mjM?voop4HdyZ z4#Q7(NTqbU$P7o%Q%j*WA~MFCtj3*6!nEUt+}z0OmL8=%dufsHn~>x!`kdVL8M?9$ zME-=>ACpvl5em{;rL4FS}BfdpTJ>#^OYU6^C#ErFTb2PibP3WT=)S z@D39Q9O2C4 zC}%11o`-T%I#8rZ9Lh-!R8s5e_>N0mBueUk`_w+L1{wD&7Q#Cx!h_lb-sT`~Zh2zf zCs3$Aeh7%BE5j!yA5{i%?FSw)125kydF?NL;n#%hPQe|VuuY~LPK2-E_JW%?Y>~B$ z$+^9Eg1MKM#=Wl2{@&KR6Q0|T1+0F3-HpW;+%5KT`}HjqPGgvQVc>|nIniH3G*=Dz z1{kVG8Dw3xuwy-ON{FRZt_qY8=UgYgJq>@!oOvcTo?Y@VoS6+Ow+mldIs(V{Wl^E! z;{G!4!BZZ!2n7WDuqvAOaizGf_SE&}O2n4f_`aan(BAdc4)EUi(;jD{3tFnYLpkUA zIOESBH*k&{uN&pu`6Z9^1K9s9I{y-{wcS5s2Bmh&v&VoqD`12)9ec>*~pE zY^Z9#?Z2Tyj7Q_PR%?e1F60cy3+f+;#AhWj>b|NTBadHJSxQb2&ly31jXNe(z!P;R zSN*CnFH{|fN2waL4nb75XFhRV=0YKA(L{pS7UO3; zn?8EROOkv#b(gmn2{f-Yo}PF#)ZcqEu>%MQoBP7!4`)*wPDY6Zj-dA!mfogk$LmKf zJ>HZE>D_e3O!r@ntlU-X@NLg-+^vZ+5?RJiheb^ADYx6Ck0}yu|Gks-rnSfLuc0!p z=YI;daCxm7|KwGJSrBXeXtFa;G)&JgbPD+D4)}Dx{abs;B4cJ$&#S%g*|G$d1P&K z;iVD^Z~X#Pdlv)cn=3et;wdWj^(7kupX+|zz1PH9c{m1AA1slZ! zwGmZs*vQjM&RSQ9Xf{0rGAp>H2Xvu?liyQmF1D)XMdo-<7O!r@$v%Rw2SUB>xM~5C zB_w6DT^Oe;U@>)XG*Cb8O;+4&{mCQogrQ+zas@1d z0zqqUCSFiFh9;N@?po)ua$+F8(8vZ#bt_+%v*ECYbmqV6<|c@_j`6nsSN0(??670mCCX7r?kciK>2ucokdy6qc&a%wr6N1_+Eoe>~Ae zuS1`Xtv;qvLaXbp5laAzN2ivvYs(e2$EK%W1~96;9ZatJMXk)yiA)lU*L$;iGs|w9 zyf(VkMUpOOj!o3Ir*5gDQ4?#-Vo4wd;aaz2qR_G4#fw)!T*OTPI=6OKi~Nr4;Eq$O&ugGz`dH;hYI zE~19;8f8nv_~?L>5i_#T<#A%-L3Est_K~J}V6yH+VD&Mn(muZ1afFo{sqMBY|LuHS zXPJ*LjxKi1s1jl*-TaSCzc zP~2A}BF&X}Vj6dsSH3!E5#@!q7v zGqG&Qj(h~2J~Etd#z$1Ij_b$$2}xz5f|drA>rbjM zpV`W48>bA2NNR3k?K4H+D>s!q(`L53)Q4qvfpirDr7>lmpnw~8rO@0+Obm!mI$G%I zkfsS9DH-_@oiy}V_Ynrfws|NEiM5+?|I~_uzPaH~HgfYJ%bw`{n>|st2)!0;Kr=(u zc@MdsCYL*p^VXSF-nEU{FMoo1!JcC0G{gn!^Gum1tdD=3FIa3nT4Ad=PximT(QV>@ zJWYQokorNu;QB>_Og3ipxFCJ>IN#3W6aQT(4+>DX9U=x8q#OGNY={gTl2zCqHXX0M zdk~b!-$m$k=1@;D$6Bq42OPl$y{9fsVzV%u+Tn*~G1zwC(-dG`sjgIgA6 zLtDII`Bhb@?+C7{LQ1QtQ7r0|f1(!k)}?7>5Cg@5Ek<#VJtdKLu(>4;1J)QX(_WPz z#tEIUb&;(ir86_XAGuHKCip1G%iNmO#B-)3*W$V^lCq)Eu^3mq$AwEsWIX{vD$q(U z@G7vbPD0W>p3^dzA8?6E<0pIr7BjATs-2lEv>veZI`+H}`UjvhWzC`%Py^7_ASDGl zp?d#LcgQkJKmsKbwE2fa^@e)6wzHcYhQkFLi^Rp$TsKyLIp3(Y-c8Ib%*AxNV76bb z+3z@@-wP|Zc&n)FcRCZXrm@K4GNq>KXXS@8AncHdFkD5K<8-PvU%= zA~c^&ccY7Z=>nQXV~!_kK6W z<9?))Yf_N5PT{Fq1$2AySin+{5}f3xjaF>*e2D4EHp`vniszFa@^1Lmg7j*_f`ZtM zXRS)RT+xMpVhBk*DmBWV=8hCU>)fBbRBv+k5{TG&J0M!v97l`MoKF zB|7oEvJ!{3DgW*fJVPp#Id4<33_l?QoiO!%FNLe}AjPKH`yQZ{VOHG)$!XCg0V7`7bkPK{2Kw~6s}j{NvYPO1bxf6 z6g6AO>-j@Gd7mJ};je=BtFc!pZXj9q2gE;13-{M(Xp3lrrL*p(&ukSGEh{2bxOhWQ zJL*jiwbuMkhYc)D5IC~GJTX(qcwUCbI#`#GU%u=U!j`5!KWOuOJ#R1&;Jn8w*}CjRq;jN4l$lKXH>y|5KF&Q9I94BWQtk{ zaMZ_TI-YTC^+?gkmh)Q@MbqO__k?gb5n+3?kB45t=qTpIDP_Ze zGKp8^1ghu=GL#e_3(en|pZK|9YB|h~sO$>-ynPagF*!{|SBuS{l{j?pMuh2`iB4)N z{3x6lDILK}9xt>eWfBkuKY?J2>{53^{YOqk1SIu_ZLJw-?%%1Zrbg}eWI-{Hs&Qt0 z!RPv(&j_}DBWNCUp2*X0lf{vQ zUWo($if9DleQ?z2^#*}?MM$=tLdcyfd$x$1Jks1S?qr9~z>11EjpZ`jY?y?H*kf?U zs&3X=n`fK9FrZMXJaL==8W&So;6R%(0(I0jQiT%XR~oZ8-TX86Lmw}sGyP9y%848j z&?5AY;GN+BsgA>eK$&F*JC-`rLIJ2Tj1(2-FTpn9@Hxck4j;v(7p{=$b*epf^7LGV z(BDOpVWBWx_j$dGt>!L!P|-f?sHe+*LCWx1X<$O$iqyI)?gwZD?#?1>bn@mPb)oet zx}kgolkXUqx}o6f>IYzQVCiT_`}_aGQ0Dl1%l=+{bN$ceDd)m;cGVX!J_`Q@!bv?) zPW{w*JUFFr199@4)ND@g`1zo+hY7b~^!BKY3FZWBgn8-KIEk5f9(MPC753%fQ1);8 zPa%{g3fb4lmXIcdC~Mi3osu;%kKGtUQDoouwQLb4`!+~O7!)GLR`zvbFm}JsOg+o@ z`@YBf`)7`E_~X9r>pZXXIkjT{aW>M2*$7XLN7IJIBeYI;Y(;abJIy-}KKn6k zbikNvC_j1_BBEgDLy_z&fc+Ym?B%*YCcTUOlT{UsMR6y65H0paNG{d>k>7s2w8QkG zuWUKUxA5M2EA^t^qo}K-QDIB(dzxozyH-|Pww+a9azWfrg))%OV(ni0G`jD(@=XTr z?RXC>rd(KS;Fj6;>C5UF=lF_amxf>5>5x&;ChJ(K3bRzTp>LiKftR+~Y>L&nY~>fP zit7(pCd57De38~a;HSo4oi<$Y%|m%JZ!LY8=Jb>wIcLYob&}RARITx6+HbU8DGYdy zYH>NfVqiS+Fv z*rg8}rP`HR8XTL@mtE)O}uY>m0px@E$$}d&Z$MGSo(CvhV zR4lYR|2gvTfN3ax`hL^#QfxSU_NnjrrZH-mzUr0ca#jBGg8NohM?b!gODrnXboajf zGC40l?9e-n|I@qS;74EZY_0rwjbW~wcV>x@_iU-z&dgKPPm>z-_)g&gU5Ls1n?p|G z;>U->!#R&I?5jsd4AM!g^qlhzY2T|I#cpSubI#h+VF`4FKA991E0K%!k6gA?T}CeR1113*E+JF#Q}is$U(}veoR} z-pt%JI~tcOpiy~!xYs#Qhk5POB-%i`{BnEYLWZwF-*@QDlVBdKGQj;@B130kZN@^+XmcM{$keL+-PEpa=FAGpe@rH znpoqf{i-9*eZi{|e1+z0@IODR6dRBWr#DNn@zcJqWcAEp<~4X6t}xt{_fG*&U%^+w zH2v_S_`4B#Iiho0P+smngl#5-nM4Rm!jg!MR!v$-g!Hzxe!15KMR8lI_%rY`rcNt_ z&m^24T76a9baB6$EwPicjW>3GCK9!ZaxNQo#!4#5X?+u%3h-q){Xmi(PAUW!nS-kC z*Dbv~SbcINen#tdhFEFVjdNP&oHTRC>(x)FIUs&G1)JkM?CgFmNlS)ljkRW0;jTD| zNsS76KEHfYc>n9Y`5}v%_Jh2p3Of5AG(yneuj9hU-uUT-It-0!hW?nAsKQum#?X_K zy6l@>0`Mwy;GVpX@R&%t4Ns=Z(F$FLjQlshc4g_ekYp|Kw=|up-h(KOEqwj-aCOM! zv|-EE+q$0cVd3r0Y2=ec!|gV9k`Gcl&GCI7 zHg@jQoX=oyiO)*8++lf7KpiNDJl*fN`_cjD2Iv8^|)_? zeRTXe0j=j7<1b4{+eF45- zpUs+Qy_?u$YCw5ZGZ+jJP*$}M7EAP+wI5l;mnYg3{u}4n({We%k_O5ibWlhk2)W27UhY(dwhm)WLLfid)e8E%WjsF!qexP zw%d4PP^*U<$tZeMwY=)1{mZadTQ`4R=bdX#XjI&lZ{D)Lt}HJEO5M-y#_0GBmG*;N z^Q2aX&NHsFcT$+143{4Vi1<883iolScoJIBqu~F+PpqA}wx0Tm)x_Y)5N_ik3jMxQ z+k@256N%R1*T%Q_S}w!2h*VE7Y{lVh@8J(Ap=-}%lua%}7y z4#eL~z`}AMzRYvV+wZITV(o<})UYxC51+&|hz(4~vVOw1ws~?a`WoV(6qz%^EcfvjcY7M6L^~L26^$V#M>s18`)*tUv7EQzC-ONU7gjW;C{|` zLLJXnD{)3WE*CTamCK-OPEfAFk91Jg+a+hpXG+4#uA@Xn_pYm=Yub6=Tpn2EC)B7v`r3c!Q$;nw+f_TPV>F(sOzHpqy7rK z0((@c5O$v4?t<;ElZ{>rZM4%>!oHCerZ_Ukd$+{j@<7EUPoxx_MeUG3)}0$fs?CD@Vwz0P%OlCWm?P? zuNv>YdM|ipvf7W^u6U~#4z-Bu8Q-hbwr){yp2=*$k1`lD-ryA4ziM^#b*j;VJa%Uv zdAWO1{>;+IXx|xC+V19>WV~+bv$vQ(_~x)<(O&TFuAM)J{xC)Ri{NO@dK&vM^GAYd zRnsq0lwZ%1IPA6w1y7i6M3I;jY`c+qG=Gmzr|e!Q-`#1f4fjV0$xcf4m2|`kD(Lt5 zz|YF{HeDAI6H^fJ-#ci~@#)^eNgQwSN*tA(`9g7oZI00-lhjS7;qkJD`!<;Oo%3pw z1vl2G#$HrPmqq&x7Aa&74+J{F z)&)Zp?^5yo!t|^jE7xKssiAG%2R`Z$vbiFXjap+<`3@T9=B0Bm*OsNJW7gRaqqa!P z*8>&EL~%`3B^SK?yVV>df?iG=bAnkG>a???di0G~yQI=G=Q@c1l(u{4c$`0~_Y3~Q z3NBrAV`t+)W`erA!Dh2KTf}1Y(xXIwKJCTIjW7?H-JNyOhF1J>n6b(IIq8Hc*sG-X7cJl$UD+bXgWORIxZ`;f*k-d=hs193-NzGxQ9*r;_f4lf)fY|CVjeqdQL2q~JxLc->+2jU!b=q|>fUa)tg!@W`B74|g5p#Eh7} zR&dxM5$845)sfg}-8~uq2~PEmg#8(ak4P^@lzOgAoEp=7dU;7@Off$@bIWCKYz~nu z5rX%!!eKVjcGs7e_bpJ`EI+32rVN&=el)^I9SvZLF?SEW?7j`GfC_r~4QSr}2Rkm;L9M4AgX`F>i=J>FpBb$Gaf9#A7V=kZ!}F3^ z!M~ZIbc%*=JZ`E>#4tIRyX-yNgHr|*u}|Y%FIlXiu6WI&3$g-N<67%i$?vblC3&Ss zk9S<|c6DziKk}Z6T{-G_=Np;d(bY87S5s5??^sFYrdc2ub(GE3VB zObaMuJMd>p@5D>kRe}x~iX(I8?)73vDpbMyRy0T6Jq#?iXf(NBVsg>R$*J6Rwky=Z z$!XQ_ezDPdTy|dGtUwER?D+Ef9h#648%Q?;zr!1* zXX-H7&uoc>P-Fcf$EHJ-NdKLftJ}->}23x888MMIV}g(?7`9D zz72Rr;j3JK@IYi6{Mz`&HU?^lE;Vo1W5|eYZXRhuz?*X<*)}1BXE-+xjE|3F?dRi< zY?p^h6e#QK>;34TjFjh1ez~Z=m!_F^?U3(Vtqbq^Z96*wZak?>shY>ltl(UkZ0sQ4 zuTmZ<=M&xHxgrR4`~$Axk+Fd|x(54!3|_Amd@xQQNRW+|$`}dI5bl=gpe3o|gsNY9 zsSC|Tq-*mKPQ%T`RD-}3-nl!Pc2JcbR&k{M$lK(}1~2HP`FrSQT(2xcpmn3R=i1l^ zmdhB+%GX;#5xdo-SUv$!8?vM0TSf%7Nf*+*3B1XusQ2P*KNFu9B5*s$AF2++6V&lal zK+NFJJ|0Z9)3O)g%bUQbP#uycX!H}V+#yAY=s~eJk(7lVpS>Q_N4skW2vVN0K#fW6X&=6QVBW{m5kEy0Qxn?*8V#Pts+}q?~U7URhjCX!D2A2>3 zaz+S;r4GwFsQ4b_YX4NH&*VQD1Q^nsG$!@X_(>hhn=8ZhP+6@cFw#b^IUAe$-yBXe zH>zoynl|F{yW*4!prq0lIgg`i%?%a(VeT6OlYC4}m8AwcO&2Fbu<*8nDA45dK;c95 zM+q70H4Kfc#S$a>8@&BfJ&aR-2N!}92}q>*#6tvCh@#LVnu_o1i3CWY<>z_%&OqXH zMsV$eVefNMJ(r73t$wNT#JLCFghj!3~e5J*aS^A}f{1}Qu^D7`Z zbE}Ih3`(pH>>^%j4SL{iq8I|re^>;rIweCWtsek`rHn& z@dZcy7vn~0@UUJJCA>EN-0E?o4lP!0nZU4Nz_9Gq9Ad(RekDwJ+9~!W%(NF{HSq~> z-Xmkz%F3dk!mAx6o6%_OXrbDhwz$&s29&c5A*qq+08^oP;B5t0g~>X7va%O9e^cuh zv;_M9W*U)TdVN@~rhh?NV=?xQ3i`@3lE36UGt_;STr_!rn- z%wJ1d%UTl{J%+y;nuHHM1a;f@zqWe=Q$neN53*9w_t)n(Hya zZJlIM2Iac^uX6oGK^Lthra?unFfLuiB__UN0QKjxyGu-)=F_Z$F;^&ww$G&Wih5Yr z752iS0kvV4dP{j5bJ1peaclj>Qc zR2K~12&zI@S#=CAK&XR=F+BAW*A$2i5omknC-FO>M*hxVNQSZwiF_fAS`h$!NHHte z`hjA<9OYL=9DxNa|FwtsdKRbB%PRg$yas@HiCqMU)f7|!=4m@XReA|kG4DYL#2nhB z2da{iPy;`1gb}NefFOcVk)6~xP=;dXlm}qj64%WllBM{YAU&D?q(}cPL2*N2z#WrN z{^vT3yCfOnI&s$yfB_#w(cwa4KplDjEtvDrfM0zK{sW>*6I}I}LCNJc%DFb_xwj$w z17yf|2%?Z3vk#arPhfi!F^*sHlv6ClgZdQY4&#yr$22BKaKtV>ZPJf>3X1X493}U2 zDn25&FB7?antme)PKVQw7KhG&>d)v0{k3ukCHJ`LTm1H#4+tnC9eEz)97q#UDN{xN zm2v`Ufn3qg11U1r1}AQa+=2k5<+pKcUAS9nJkb`iK;9E$06|=TnC02G^$aWWYG4bGZ5;l*P=b)daf~ zNP=8OBePUgex;!_(uxC|JSkrvBA~4f8hyQw$G-ZHNn*Z1-U$`^`N;_&#%Dp9r*(Qa@QXG=ZTNKB~+XFuY6y9Y%vQ?`ilu}HowwK^|#>a z%>VIQ^VL0W5-8RNV^pjlv!)wVd}=^GDEMqpOzj4p(q2F>CqW--_*TZgkm)Wya~7x~ zUoMh=AoulhaoV%I{tdhTJhZ_rG^q9%z&ehI)S7nRGSGSe(*Usu^roLTCjDF6(| zePZ<`nl(S$#WyfRG+?rmG?I7zPA80A8W{kjRPy(ce|6sq3PO4RRni1r#cmk`sRyWD z1s&#JRsH`vE{2Z*SDIeaj*7LGf%DDx#BWz8L%@MS({r^D*T)#1BruBZ=+Xn_~?CLoZ?p!goB^$cU2}*U6z0$&a(JMNaik8TS?jhd$6qy@ANQj$zs%c@O zRL}sacpSQ`N9Y$dv#6B*2}T^avB1g|NQNnax%F6W0&|J&m(ZbIGKuPtD*CT{Mw^gR zUIV0+;pd}X*cYW#^SrdEtX@!T{O!`YAlewkz*C*szlYed^6Qe@ufnoJ>H zR!JO(Ol@sSv48Bb6qbdc<0z?dLf@jg?0slfZuwezEmJY$r>3U1xh3{S$jX}p{LHi) zMEpE+4-T59#PNrBKQ_L*Ez^Ube53Z*$tmH*KxQHx?d^To@z0K2myk8bhcFtyKXb44 zLKD_@TrzMSjHrT_KRkkJkUTvR6857KzFD{MMJW>8-p%@H8JMuI-9t7Khe<7~csY@Q zG+8&yGW@Yw;<2n?;gb5~aCXa2kIgM|Y8GLf><>&peL5$b0zTN|+HIBatjnUNn@#;5 zBhVdra=1*cjdNf)O_WUm&AA^X&eud@n6;1Yo^oU-o!?%to9hJcLYnaykSM{5!~6K; zphIHOA9eRqoT~%<1|OL5uU6I<^saekAG>O%(^xRFPA{ZdJ9TVsPsD zpru94pk(tJ^_~EY--Vw5mgKJ{_P4SKwt!AbD0E)ZUmupy-W$}h*3WZKup1haW>gTy zhZ?>I>oFGF)rSw0sr+2?E1h22e66l3w>4MITJ4Ivk2ZBjC%R~(*C3RWObJfZ<=5k1 z(_j+Srb!;z9Mw-9%Vm_?t{E|}2haU%DpjW5`0N&zd&kDA&%}5K9c}OfQk9H#NMvp$ z@2*Ws&2uw#H^m3tH*QuxMq*p&!_rc1hR(q#jgeMhR&4@HC9j`1kbzLG$I& z=}7jxWeG`lk!WLF+BB}nqQ8*M4jU4;uzHo+c69RRmsOa&{=$QDt%2lac){CiXf;`4Cr(YGeG2f zK&=obk+@QbCFpE3u%Vm(o`-%FMV87~=k7k~A-!zibSAm?WG4(Jo8%r#` z6WG+J6jSnA%FpZzPV5cNvL`{dcSV4la!^c=2|sIjtEu34e=rk6QV9 zIp5ywl{6E(Ps#8LhnbZXK@nN?i>61g*sl?KI?ac$iQ+8LN2lerO>KISH#>52F$r8% z$+Ys&IW#--e*|UG) zN)UMxf=vL0g%}gYb`sa@b6oKth= zB2uH3ZXoe?&O?Z3Y+-AGn*NQh23qyD14L`Ci;GC8VNdiI+Jn3N&1_NEXttfk5G{_& z$2Da8;=WH>)E@JSVJz7A0|i7c`DR2Nk?vW*8J&e*|MdAwTMB zcNfojE8ezqYR!tYLYY|rw zzpihx^G!Pud$OLDeCM0pT;KwD!B7Dvi=KsD4c)TItnA(s|G5PD&!Q);S{GR>IsYLC zf6){|Rwl2|#mG6nEHqCob#Y;~MWV5Nd?FDgggmWkk(fRt9g-||_S2q;zO{qarfIo| zx3;YYPQFh+UTbmb<*dDSL9wNTvIV#eV#*c-S6G9p>54d%6V^NLTgNu8UXuhsUS1Ov#QA`O9Lg4D2>$2jASj zfLjL9rr2hu`fz>Sdigi|c1-HsoSBKzJvi$Pth@V;M9NVc`kgcQC5xu=e7uI6+t?yK zX^w#v(@;$R$kki?Q7rV4L79`b)-C|g0q!%bXc5LQ(kzsA2;VZC_VR&vN*3!X$GgWt z;TOJss|kGSv1X5uGvFFt?K^?cnn$!u7m%75HmCE8w##78w^)w5ccs3FkXUQs-oObI z+|gg#&h>bd1XIX@Ou4c9dGd{yk}`zsPSx7{V~RbZ!)pWu=DIs~`3UQdoT|Am@!R$$ zaH4%IsQx|p5a&F?Tm^=V0@BHBEy~{;m@Q!Sfo=QCA~JF^yezWfol6*6l;AlJkx||r zC_h_bli8Yx+VjuouaAEHK>#3CJLxBSu~}P)bbOe7M&8TVebeJ;_cYlf_pGjRDY1xn z7h9qA%&PLr^@m`o7TjMv^K$n9-sHbCAdw^3EM^p6KbtJDzU?{w#E3`oqXL_D2uDm( zOYij4^CDWC6D!jN28|2bXIO)t-{C+T)30P{4RfF}N17I;8}wCSLb1)&S81JD*(2Xv z_FStCsBt$RUATm^SE1Nv6ZJUyE`znGQL~kk)Kdw69Bn*TRa~#!aqHEJn6H-a!TE=d zKfTAj8Y*ro?d3Svo7i>LlCxO5tl`8g^YfPS4R*cdpzp82MxZh74fF>5a}EDxNIJcf zT!G;iheoA>vDY`UE@y6BaP>ES8=*S6jN!)`FN6KH;pD@)mXZJFJEEm!4QSrlw zeb7B(_fmQl&kVUbkD*0{GVSAkrYhEwzSrjp( z-IrlcoN;oF-*|bZYlZ>)bMF$t4u~?CU2cv<=`&4H8Mgjq26QS z#qt}b!6aF$rk~R1!gk@&8yfy!H7&{okZA{x_I6Q=IM|5S45DaN<0iN?N7cG>ns_%& z;BC|$Ftc}qv00c|%F-g4{cno&PtD>w5;f=T^HlyOeIteIh> zPA@}oL^0-xv9NjjZ3L&{%-GPppCPG9`ICW@DNjmXtTu6eO1$r2I!qTLZl2_)7#MzK z;BKJQGN+GX!RAomQShhh6}<@U;L08eJej`$S4r|PB1PUe`M}T5t<=oRnYv3#v!|7fvOqqSAks`cF2ic z4ZZc>$gzm~gR2+j(qPS?%?ltS?pOZh7uZPwdc=tI)ctIIS(jS2J~d)EA=-DG2bKAq+wpw$;pR zr2}JnKiL?+p2xLJj+aQbdNkzVCH45l!t>LhaF^t5g*wQ#j|^RqI-eB2)9f~JX`>2@k}`HeuR z9!c0GOc+{R@Il3nHf(=fo1uK^417pq;EYS-1YVLEZ{_Ap>OWkr z!hCr1XuCRzv%7n*rbw7Vf#FO%PQy`T3HhXf5N> z3#iD&Kk09D{1BuiM=IR@h}MMUD79}uR#4*CE%4^Y)yr>gr5^EGMg?-R2}Z2Dq~>0B z`ry$q?pC?5OWt-+KO*ta`^eY9>^wHuZDOP&sx+key1?L_klpODEM^|wfa#VoJLsdx zl9OGb^EdpK^3CVwdzbC&_l!mD8~VRlO?1HYH*t4I-l^r!Efwh|rn+^@4Tm}rt^rEyFs7`~CUL|#JWrqVM-JxLM znygcUuPN#;@n8QyGQ7B{f@gLQ`xq1snun_xR-lgUExZCP87{eJ|GrixF9Ht0(8 zl;fKP>x4Y8xX{E{0Y$61_j>#8;M(E`!tDs^#A|8FicHxQc%`AH&-YfsrubYZ%*-&Z z6PuBmJo8(xEyP_XD0~jNACSuJwdlOf=2S5zJzPNZyrJU`%T{?M62P)cp-%Gnxd7-O zOO%_3Dn%sqN8lR8VNfT}0>pt)(TU2Kw2Jwwkjf`kLFnjwcswL$##|7Y8?#ZJ?3IVI zs!< z;_)M}bnAI@zw8CdAxTn6J|Z4sC0`hC*rg65tFn20O`DZ~mpTi9XhJmgXFU{|D%Qx5 z2=OPEqn)Iomvha*2MT+ymsJtkz3X%0@I5%yf3O0pQ5HrZDUWwRPV^9;?XG|TJeWZM zcrg0^m6Nvcn@IAz`)PC=c%IpTm#~JOFV11^7{PJRyMq(I(IMy>T8_*-e6*IS;uQY% za1&RxSUfm-7-1`9_9iI~P#xriadYbr!Y=PHx|?UA!vkdDBFMri$Yk~@1HERhk(NgzT$?P&1vH`8@XtVSpM)d<}#0pL=D;Tqpo9}Ef^m31OwqDjD{t|0r2 z9+SK7+iy%w+sb7>LSYv}(jiO>U@bvehiclesMessagesTotal); + sbufWriteU32(dst, getAdsbStatus()->heartbeatMessagesTotal); for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){ @@ -977,6 +979,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF #else sbufWriteU8(dst, 0); sbufWriteU8(dst, 0); + sbufWriteU32(dst, 0); + sbufWriteU32(dst, 0); #endif break; case MSP_DEBUG: diff --git a/src/main/io/adsb.c b/src/main/io/adsb.c index 573112c2df7..260f89fa6af 100644 --- a/src/main/io/adsb.c +++ b/src/main/io/adsb.c @@ -131,6 +131,11 @@ void gpsDistanceCmBearing(int32_t currentLat1, int32_t currentLon1, int32_t dest *bearing = wrap_36000(*bearing); }; +bool adsbHeartbeat(void){ + adsbVehiclesStatus.heartbeatMessagesTotal++; + return true; +} + void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal) { // no valid lat lon or altitude @@ -139,6 +144,7 @@ void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal) { } adsbVehiclesStatus.vehiclesMessagesTotal++; + adsbVehicle_t *vehicle = NULL; vehicle = findVehicleByIcao(vehicleValuesLocal->icao); diff --git a/src/main/io/adsb.h b/src/main/io/adsb.h index 86eefd8aac1..77f2e31fa47 100644 --- a/src/main/io/adsb.h +++ b/src/main/io/adsb.h @@ -54,9 +54,11 @@ typedef struct { typedef struct { uint32_t vehiclesMessagesTotal; + uint32_t heartbeatMessagesTotal; } adsbVehicleStatus_t; void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal); +bool adsbHeartbeat(void); adsbVehicle_t * findVehicleClosest(void); adsbVehicle_t * findVehicle(uint8_t index); uint8_t getActiveVehiclesCount(void); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d682c0299ff..fff22479f06 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2136,7 +2136,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ADSB_INFO: { buff[0] = SYM_ADSB; - if(getAdsbStatus()->vehiclesMessagesTotal > 0){ + if(getAdsbStatus()->vehiclesMessagesTotal > 0 || getAdsbStatus()->heartbeatMessagesTotal > 0){ tfp_sprintf(buff + 1, "%2d", getActiveVehiclesCount()); }else{ buff[1] = '-'; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index c8f5600d6e6..4e8d54535a3 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1134,6 +1134,22 @@ static bool handleIncoming_RADIO_STATUS(void) { return true; } +static bool handleIncoming_HEARTBEAT(void) { + mavlink_heartbeat_t msg; + mavlink_msg_heartbeat_decode(&mavRecvMsg, &msg); + + switch (msg.type) { +#ifdef USE_ADSB + case MAV_TYPE_ADSB: + return adsbHeartbeat(); +#endif + default: + break; + } + + return false; +} + #ifdef USE_ADSB static bool handleIncoming_ADSB_VEHICLE(void) { mavlink_adsb_vehicle_t msg; @@ -1188,7 +1204,7 @@ static bool processMAVLinkIncomingTelemetry(void) if (result == MAVLINK_FRAMING_OK) { switch (mavRecvMsg.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: - break; + return handleIncoming_HEARTBEAT(); case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: return handleIncoming_PARAM_REQUEST_LIST(); case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: From b32d14d701c9a670039b2b27b20b7a73a344d330 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 10 Aug 2024 18:25:32 +0100 Subject: [PATCH 179/212] smooth xt error rate --- src/main/navigation/navigation_fixedwing.c | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 0c49ad4fda7..3f814513edf 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -408,13 +408,14 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); - if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) { + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200.0f) { static float crossTrackErrorRate; static timeUs_t previousCrossTrackErrorUpdateTime; + static float previousCrossTrackError = 0.0f; - if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(10)) { - static float previousCrossTrackError = 0.0f; - crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); + if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(10) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { + const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); + crossTrackErrorRate = 0.5 * (crossTrackErrorRate + ((previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec)); previousCrossTrackErrorUpdateTime = currentTimeUs; previousCrossTrackError = navCrossTrackError; } @@ -424,7 +425,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta adjustmentFactor *= 1.0f + sq(navCrossTrackError / (navConfig()->fw.wp_tracking_accuracy * 500.0f)); /* Apply additional fine adjustment based on speed of convergence to achieve a convergence speed of around 2 m/s */ - float limit = constrainf((crossTrackErrorRate > 0.0f ? crossTrackErrorRate : 0.0f) + navCrossTrackError / 3.0f, 200.0f, posControl.actualState.velXY / 4.0f); + float limit = constrainf(fabsf(crossTrackErrorRate) + navCrossTrackError / 3.0f, 200.0f, posControl.actualState.velXY / 4.0f); float rateFactor = limit; if (crossTrackErrorRate > 0.0f) { float timeFactor = constrainf(navCrossTrackError / 100.0f, 10.0f, 30.0f); From 3efc75e825b443bd3810bb3dd62f04532b544d93 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 10 Aug 2024 21:52:54 +0100 Subject: [PATCH 180/212] Update navigation_fixedwing.c --- src/main/navigation/navigation_fixedwing.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 3f814513edf..751c0698b38 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -415,7 +415,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(10) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); - crossTrackErrorRate = 0.5 * (crossTrackErrorRate + ((previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec)); + crossTrackErrorRate = 0.5f * (crossTrackErrorRate + ((previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec)); previousCrossTrackErrorUpdateTime = currentTimeUs; previousCrossTrackError = navCrossTrackError; } From f97a1020cc4183902cb2c28470d92806d01e4d24 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Wed, 14 Aug 2024 13:00:18 +0100 Subject: [PATCH 181/212] not working --- src/main/blackbox/blackbox.c | 32 ++++++++++++++++---------------- src/main/blackbox/blackbox_io.h | 4 ++-- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 1222af19cd8..f719bfc6967 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -353,24 +353,24 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = { {"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_16)}, {"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_17)}, {"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)}, - {"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)}, - {"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_19)}, - {"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_20)}, - {"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_21)}, - {"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_22)}, - {"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)}, - {"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)}, - {"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)}, + {"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_19)}, + {"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_20)}, + {"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_21)}, + {"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_22)}, + {"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)}, + {"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)}, + {"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)}, + {"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)}, /* - {"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)}, - {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)}, + {"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)}, {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_28)}, - {"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_29)}, - {"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_30)}, - {"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_31)}, - {"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)}, - {"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)}, - {"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)}, + {"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_29)}, + {"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_30)}, + {"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_31)}, + {"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)}, + {"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)}, + {"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)}, + {"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_35)}, */ {"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)}, diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 76b03b5cd6a..e4eda947d7c 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -48,13 +48,13 @@ typedef enum { * We want to limit how bursty our writes to the device are. Note that this will also restrict the maximum size of a * header write we can make: */ -#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 256 +#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 512 /* * Ideally, each iteration in which we are logging headers would write a similar amount of data to the device as a * regular logging iteration. This way we won't hog the CPU by making a gigantic write: */ -#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 64 +#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 128 extern int32_t blackboxHeaderBudget; From 376346d8f7ca6f761c5f566942bcf70a41043b4c Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Wed, 14 Aug 2024 13:19:30 +0100 Subject: [PATCH 182/212] fix typo and bug in servo logging --- src/main/blackbox/blackbox.c | 2 +- src/main/blackbox/blackbox_io.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index f719bfc6967..4341ea0c34d 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -712,7 +712,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34: */ - return ((FlightLogFieldCondition)MIN(getServoCount(), 26) >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS); + return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS); case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index e4eda947d7c..76b03b5cd6a 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -48,13 +48,13 @@ typedef enum { * We want to limit how bursty our writes to the device are. Note that this will also restrict the maximum size of a * header write we can make: */ -#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 512 +#define BLACKBOX_MAX_ACCUMULATED_HEADER_BUDGET 256 /* * Ideally, each iteration in which we are logging headers would write a similar amount of data to the device as a * regular logging iteration. This way we won't hog the CPU by making a gigantic write: */ -#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 128 +#define BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION 64 extern int32_t blackboxHeaderBudget; From 858210e14a2ba4dca1ff7aa64aeb39274948693c Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 15 Aug 2024 13:43:46 +0100 Subject: [PATCH 183/212] remove excessive `SD` debug from MSP processing --- src/main/fc/fc_msp.c | 11 ++++------- src/main/msp/msp_serial.c | 5 ----- 2 files changed, 4 insertions(+), 12 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index c8ae27f270d..b5715483f73 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1034,7 +1034,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP_MIXER: sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback break; - + case MSP_RX_CONFIG: sbufWriteU8(dst, rxConfig()->serialrx_provider); @@ -1274,7 +1274,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); sbufWriteU16(dst, 0); //Was gyroConfig()->gyro_stage2_lowpass_hz - break; + break; case MSP_PID_ADVANCED: sbufWriteU16(dst, 0); // pidProfile()->rollPitchItermIgnoreRate @@ -1618,7 +1618,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF } } break; - + case MSP2_INAV_MC_BRAKING: #ifdef USE_MR_BRAKING_MODE @@ -2892,7 +2892,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else return MSP_RESULT_ERROR; break; - + case MSP_SET_FAILSAFE_CONFIG: if (dataSize == 20) { failsafeConfigMutable()->failsafe_delay = sbufReadU8(src); @@ -3291,11 +3291,9 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) #endif case MSP2_INAV_GPS_UBLOX_COMMAND: if(dataSize < 8 || !isGpsUblox()) { - SD(fprintf(stderr, "[GPS] Not ublox!\n")); return MSP_RESULT_ERROR; } - SD(fprintf(stderr, "[GPS] Sending ubx command: %i!\n", dataSize)); gpsUbloxSendCommand(src->ptr, dataSize, 0); break; @@ -4145,7 +4143,6 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro // initialize reply by default reply->cmd = cmd->cmd; - SD(fprintf(stderr, "[MSP] CommandId: 0x%04x bytes: %i!\n", cmdMSP, sbufBytesRemaining(src))); if (MSP2_IS_SENSOR_MESSAGE(cmdMSP)) { ret = mspProcessSensorCommand(cmdMSP, src); } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 0dbc1768b8a..f72ea35da11 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -173,10 +173,8 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c) case MSP_CHECKSUM_V1: if (mspPort->checksum1 == c) { mspPort->c_state = MSP_COMMAND_RECEIVED; - SD(fprintf(stderr, "[MSPV1] Command received\n")); } else { mspPort->c_state = MSP_IDLE; - SD(fprintf(stderr, "[MSPV1] Checksum error!\n")); } break; @@ -229,7 +227,6 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c) // Check for potential buffer overflow if (hdrv2->size > MSP_PORT_INBUF_SIZE) { mspPort->c_state = MSP_IDLE; - SD(fprintf(stderr, "[MSPV2] Potential buffer overflow!\n")); } else { mspPort->dataSize = hdrv2->size; @@ -253,9 +250,7 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c) case MSP_CHECKSUM_V2_NATIVE: if (mspPort->checksum2 == c) { mspPort->c_state = MSP_COMMAND_RECEIVED; - SD(fprintf(stderr, "[MSPV2] command received!\n")); } else { - SD(fprintf(stderr, "[MSPV2] Checksum error!\n")); mspPort->c_state = MSP_IDLE; } break; From d7142fc4dab3a70ba442d11ae42fb69afee8e006 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 18 Aug 2024 23:01:12 +0100 Subject: [PATCH 184/212] improved method, setting updated --- docs/Settings.md | 4 +- src/main/fc/settings.yaml | 9 ++- src/main/navigation/navigation_fixedwing.c | 80 +++++++++++++--------- 3 files changed, 55 insertions(+), 38 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 6487b44b6d1..c5965d13361 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3524,11 +3524,11 @@ Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within ### nav_fw_wp_tracking_accuracy -Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable. +Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 10 | +| OFF | OFF | ON | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 6c16ce93b21..d3aa1f481fc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -83,7 +83,7 @@ tables: values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE", - "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", + "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST", "ADAPTIVE_FILTER", "HEADTRACKER", "GPS", "LULU", "SBUS2"] - name: aux_operator values: ["OR", "AND"] @@ -2545,11 +2545,10 @@ groups: min: 1 max: 9 - name: nav_fw_wp_tracking_accuracy - description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable." - default_value: 0 + description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible." + default_value: OFF field: fw.wp_tracking_accuracy - min: 0 - max: 10 + type: bool - name: nav_fw_wp_tracking_max_angle description: "Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved." default_value: 60 diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 751c0698b38..4d8215c688d 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -399,42 +399,60 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta virtualTargetBearing = calculateBearingToDestination(&virtualDesiredPosition); } - /* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */ + // Calculate cross track error + fpVector3_t virtualCoursePoint; + virtualCoursePoint.x = posControl.activeWaypoint.pos.x - + posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + virtualCoursePoint.y = posControl.activeWaypoint.pos.y - + posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); + + /* If waypoint tracking enabled force craft toward and ckosely track along waypoint course line */ if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - fpVector3_t virtualCoursePoint; - virtualCoursePoint.x = posControl.activeWaypoint.pos.x - - posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); - virtualCoursePoint.y = posControl.activeWaypoint.pos.y - - posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); - navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); - - if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200.0f) { - static float crossTrackErrorRate; - static timeUs_t previousCrossTrackErrorUpdateTime; - static float previousCrossTrackError = 0.0f; - - if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(10) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { - const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); - crossTrackErrorRate = 0.5f * (crossTrackErrorRate + ((previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec)); - previousCrossTrackErrorUpdateTime = currentTimeUs; - previousCrossTrackError = navCrossTrackError; - } + static float crossTrackErrorRate; + static timeUs_t previousCrossTrackErrorUpdateTime; + static float previousCrossTrackError = 0.0f; + static pt1Filter_t fwCrossTrackErrorRateFilterState; - /* Apply basic adjustment to factor up virtualTargetBearing error based on navCrossTrackError */ - float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); - adjustmentFactor *= 1.0f + sq(navCrossTrackError / (navConfig()->fw.wp_tracking_accuracy * 500.0f)); - - /* Apply additional fine adjustment based on speed of convergence to achieve a convergence speed of around 2 m/s */ - float limit = constrainf(fabsf(crossTrackErrorRate) + navCrossTrackError / 3.0f, 200.0f, posControl.actualState.velXY / 4.0f); - float rateFactor = limit; - if (crossTrackErrorRate > 0.0f) { - float timeFactor = constrainf(navCrossTrackError / 100.0f, 10.0f, 30.0f); - rateFactor = constrainf(scaleRangef(navCrossTrackError / crossTrackErrorRate, 0.0f, timeFactor, -limit, limit), -limit, limit); + if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(20) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { + const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); + + if (fabsf(previousCrossTrackError - navCrossTrackError) < 500.0f) { + crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec; } + crossTrackErrorRate = pt1FilterApply4(&fwCrossTrackErrorRateFilterState, crossTrackErrorRate, 3.0f, crossTrackErrorDtSec); + + previousCrossTrackErrorUpdateTime = currentTimeUs; + previousCrossTrackError = navCrossTrackError; + } + + /* Dynamic tracking deadband set at minimum 2m for baseline speed of 60 km/h */ + float trackingDeadband = 200.0f * MAX(posControl.actualState.velXY / 1700.0f, 1.0f); - /* Determine final adjusted virtualTargetBearing */ + /* cutTurnActive improves convergence with course line when WP turn smoothing CUT used */ + static bool cutTurnActive = false; + if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_CUT && posControl.flags.wpTurnSmoothingActive) { + cutTurnActive = true; + } + + if (cutTurnActive && !posControl.flags.wpTurnSmoothingActive) { + virtualTargetBearing = wrap_36000(virtualTargetBearing - wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing)); + cutTurnActive = ABS(wrap_18000(posControl.activeWaypoint.bearing - posControl.actualState.cog)) > 500; + } else if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && + navCrossTrackError > trackingDeadband) { + float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle); - adjustmentFactor = constrainf(adjustmentFactor + rateFactor * SIGN(adjustmentFactor), -angleLimit, angleLimit); + + /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile + * Adjustment limited to navCrossTrackError as course line approached to avoid instability */ + float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit)); + float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed); + float limit = MIN(angleLimit, navCrossTrackError); + + adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed); + adjustmentFactor = constrainf(adjustmentFactor, -limit, limit); + + /* Calculate final adjusted virtualTargetBearing */ virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor); } } From 601945e00dc6b756a6edb2e6d21391532e125c96 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 18 Aug 2024 17:54:04 -0500 Subject: [PATCH 185/212] MAMBAF722_2022B: use DMAR for motor 7 --- src/main/target/MAMBAF722_2022A/target.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/MAMBAF722_2022A/target.h b/src/main/target/MAMBAF722_2022A/target.h index 4ab5a75bbc8..cf834b11ea6 100644 --- a/src/main/target/MAMBAF722_2022A/target.h +++ b/src/main/target/MAMBAF722_2022A/target.h @@ -23,6 +23,7 @@ #define TARGET_BOARD_IDENTIFIER "M72B" #define USBD_PRODUCT_STRING "MAMBAF722_2022B" +#define USE_DSHOT_DMAR #else From 42a125994cf7f454a89151daa18447d0fc60472e Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 18 Aug 2024 20:11:59 -0500 Subject: [PATCH 186/212] GEPRC_F722_AIO add target with UART3 instead of i2c --- src/main/target/GEPRC_F722_AIO/CMakeLists.txt | 1 + src/main/target/GEPRC_F722_AIO/target.h | 13 +++++++++++++ 2 files changed, 14 insertions(+) diff --git a/src/main/target/GEPRC_F722_AIO/CMakeLists.txt b/src/main/target/GEPRC_F722_AIO/CMakeLists.txt index 51e664a2637..9116889a26e 100644 --- a/src/main/target/GEPRC_F722_AIO/CMakeLists.txt +++ b/src/main/target/GEPRC_F722_AIO/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f722xe(GEPRC_F722_AIO) +target_stm32f722xe(GEPRC_F722_AIO_UART3) diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h index 5dede599778..3b2ff13f0ac 100644 --- a/src/main/target/GEPRC_F722_AIO/target.h +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -17,7 +17,11 @@ #pragma once +#ifdef GEPRC_F722_AIO_UART3 +#define TARGET_BOARD_IDENTIFIER "GEP3" +#else #define TARGET_BOARD_IDENTIFIER "GEPR" +#endif #define USBD_PRODUCT_STRING "GEPRC_F722_AIO" @@ -53,6 +57,8 @@ // *************** I2C/Baro/Mag ********************* #define USE_I2C + +#ifndef GEPRC_F722_AIO_UART3 #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 #define I2C2_SDA PB11 @@ -74,6 +80,7 @@ #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C2 #define BNO055_I2C_BUS BUS_I2C2 +#endif // *************** FLASH ************************** #define M25P16_CS_PIN PB9 @@ -108,9 +115,11 @@ #define UART2_RX_PIN PA3 #define UART2_TX_PIN PA2 +#ifdef GEPRC_F722_AIO_UART3 #define USE_UART3 #define UART3_RX_PIN PB11 #define UART3_TX_PIN PB10 +#endif #define USE_UART4 #define UART4_RX_PIN PC11 @@ -120,7 +129,11 @@ #define UART5_RX_PIN PD2 #define UART5_TX_PIN PC12 +#ifdef GEPRC_F722_AIO_UART3 #define SERIAL_PORT_COUNT 6 +#else +#define SERIAL_PORT_COUNT 5 +#endif #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS From 3c88f0452e0d600f1ebdbe5a1b11e4e2c3e12ffc Mon Sep 17 00:00:00 2001 From: bkleiner Date: Thu, 8 Aug 2024 11:55:34 +0200 Subject: [PATCH 187/212] add TBS_LUCID_FC --- src/main/target/TBS_LUCID_FC/CMakeLists.txt | 1 + src/main/target/TBS_LUCID_FC/target.c | 52 +++++++ src/main/target/TBS_LUCID_FC/target.h | 151 ++++++++++++++++++++ 3 files changed, 204 insertions(+) create mode 100644 src/main/target/TBS_LUCID_FC/CMakeLists.txt create mode 100644 src/main/target/TBS_LUCID_FC/target.c create mode 100644 src/main/target/TBS_LUCID_FC/target.h diff --git a/src/main/target/TBS_LUCID_FC/CMakeLists.txt b/src/main/target/TBS_LUCID_FC/CMakeLists.txt new file mode 100644 index 00000000000..0f7f65f2625 --- /dev/null +++ b/src/main/target/TBS_LUCID_FC/CMakeLists.txt @@ -0,0 +1 @@ +target_at32f43x_xMT7(TBS_LUCID_FC) \ No newline at end of file diff --git a/src/main/target/TBS_LUCID_FC/target.c b/src/main/target/TBS_LUCID_FC/target.c new file mode 100644 index 00000000000..213948bacce --- /dev/null +++ b/src/main/target/TBS_LUCID_FC/target.c @@ -0,0 +1,52 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "platform.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TMR3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 + DEF_TIM(TMR3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 2), // S2 + DEF_TIM(TMR3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 3), // S3 + DEF_TIM(TMR3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 4), // S4 + + DEF_TIM(TMR2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 8), // S5 + DEF_TIM(TMR2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 9), // S6 + DEF_TIM(TMR2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 10), // S7 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 11), // S8 + + DEF_TIM(TMR1, CH1, PA8, TIM_USE_LED, 0, 5), // LED Strip + + DEF_TIM(TMR4, CH2, PB7, TIM_USE_ANY, 0, 6), // Aux + DEF_TIM(TMR4, CH3, PB8, TIM_USE_ANY, 0, 7), // Aux + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TBS_LUCID_FC/target.h b/src/main/target/TBS_LUCID_FC/target.h new file mode 100644 index 00000000000..b608622d1ed --- /dev/null +++ b/src/main/target/TBS_LUCID_FC/target.h @@ -0,0 +1,151 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "LUFC" + +#define USBD_PRODUCT_STRING "TBS Lucid FC" + +#define LED0 PC14 +#define LED1 PC15 + +#define BEEPER_INVERTED +#define BEEPER PC13 + +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN NONE +#define UART2_RX_PIN PB0 + +#define USE_UART3 +#define UART3_TX_PIN PB11 +#define UART3_RX_PIN PB10 + +#define USE_UART4 +#define UART4_TX_PIN PH3 +#define UART4_RX_PIN PH2 + +#define USE_UART5 +#define UART5_TX_PIN PB9 +#define UART5_RX_PIN PD2 + +#define USE_UART7 +#define UART7_TX_PIN PB4 +#define UART7_RX_PIN PB3 + +#define USE_UART8 +#define UART8_TX_PIN PC2 +#define UART8_RX_PIN PC3 + +#define SERIAL_PORT_COUNT 8 + +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG_FLIP +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG_FLIP +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PA15 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PC7 + +#define USE_BARO +#define USE_BARO_BMP388 +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define USE_MAG_ALL +#define MAG_I2C_BUS BUS_I2C1 + +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC5 // Camera Control + +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_CHANNEL7 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2) | BIT(12) | BIT(13)) +#define TARGET_IO_PORTH (BIT(2) | BIT(3)) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define MAX_PWM_OUTPUT_PORTS 10 + +#define DEFAULT_FEATURES \ + (FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_OSD | \ + FEATURE_LED_STRIP) + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART5 \ No newline at end of file From 61d569a635c810cf689fd8608438cdfbfdec6e2f Mon Sep 17 00:00:00 2001 From: b14ckyy <33039058+b14ckyy@users.noreply.github.com> Date: Tue, 20 Aug 2024 10:53:49 +0200 Subject: [PATCH 188/212] Update Fixed Wing Landing.md clearer wording of the Final Approach phase description. --- docs/Fixed Wing Landing.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Fixed Wing Landing.md b/docs/Fixed Wing Landing.md index c89a5ee2075..3e658285d61 100644 --- a/docs/Fixed Wing Landing.md +++ b/docs/Fixed Wing Landing.md @@ -15,7 +15,7 @@ This enables up to 4 different approach directions, based on the landing site an 3. The landing direction and the approach waypoints are calculated on the basis of the measured wind parameters. If no headwind landing is possible or the wind strength is greater than "Max. tailwind" (see Global Parameters), return to point 2. 4. The landing is initiated. The aircraft flies the downwind course, "Approach Altitude" is held. 5. Base Leg: the altitude is reduced from 2/3 of "Approach Altitude". -6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is reduced to "Land Altitude". +6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is gradually reduced towards "Land Altitude" while approaching the Safe Home Coordinates. 7. Glide: When "Glide Altitude" is reached, the motor is switched off and the pitch angle of "Glide Pitch" is held. 7. Flare: Only if a LIDAR/Rangefinder sensor is present: the motor remains switched off and the pitch angle of "Flare Pitch" is held 8. Landing: As soon as INAV has detected the landing, it is automatically disarmed, see setting `nav_disarm_on_landing`. From 899a2673a72616ad1d892da1765995935b732c36 Mon Sep 17 00:00:00 2001 From: b14ckyy <33039058+b14ckyy@users.noreply.github.com> Date: Tue, 20 Aug 2024 10:57:43 +0200 Subject: [PATCH 189/212] Update Fixed Wing Landing.md Fixed some typos --- docs/Fixed Wing Landing.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Fixed Wing Landing.md b/docs/Fixed Wing Landing.md index 3e658285d61..c50bef9c567 100644 --- a/docs/Fixed Wing Landing.md +++ b/docs/Fixed Wing Landing.md @@ -4,7 +4,7 @@ INAV supports advanced automatic landings for fixed wing aircraft from version 7.1. The procedure is based on landings for man-carrying aircraft, so that safe landings at a specific location are possible. -Supported are landings at safehome after "Return to Home" or at a defined LAND waypoint for missions. +Supported are landings at Safehome after "Return to Home" or at a defined LAND waypoint for missions. Every landing locations can be defined with a target point and 2 different approach headings (colinear to the landing strips) with exclusive direction or opposite directions allowed. This enables up to 4 different approach directions, based on the landing site and surrounding area. @@ -15,7 +15,7 @@ This enables up to 4 different approach directions, based on the landing site an 3. The landing direction and the approach waypoints are calculated on the basis of the measured wind parameters. If no headwind landing is possible or the wind strength is greater than "Max. tailwind" (see Global Parameters), return to point 2. 4. The landing is initiated. The aircraft flies the downwind course, "Approach Altitude" is held. 5. Base Leg: the altitude is reduced from 2/3 of "Approach Altitude". -6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is gradually reduced towards "Land Altitude" while approaching the Safe Home Coordinates. +6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is gradually reduced towards "Land Altitude" while approaching the Safehome coordinates. 7. Glide: When "Glide Altitude" is reached, the motor is switched off and the pitch angle of "Glide Pitch" is held. 7. Flare: Only if a LIDAR/Rangefinder sensor is present: the motor remains switched off and the pitch angle of "Flare Pitch" is held 8. Landing: As soon as INAV has detected the landing, it is automatically disarmed, see setting `nav_disarm_on_landing`. From b2aef2524478104baab81235d2da43be7b2eca86 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 20 Aug 2024 17:38:18 +0100 Subject: [PATCH 190/212] bin cut turn and change setting use --- docs/Settings.md | 4 +-- src/main/fc/settings.yaml | 7 +++-- src/main/navigation/navigation_fixedwing.c | 33 ++++++---------------- 3 files changed, 15 insertions(+), 29 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c5965d13361..6ab03e46334 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3524,11 +3524,11 @@ Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within ### nav_fw_wp_tracking_accuracy -Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. +Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Setting adjusts tracking deadband distance fom waypoint courseline [m]. Tracking isn't actively controlled within the deadband providing smoother flight adjustments but less accurate tracking. A 2m deadband should work OK in most cases. Setting to 0 disables waypoint tracking accuracy. | Default | Min | Max | | --- | --- | --- | -| OFF | OFF | ON | +| 0 | 0 | 10 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index d3aa1f481fc..36646efb2c0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2545,10 +2545,11 @@ groups: min: 1 max: 9 - name: nav_fw_wp_tracking_accuracy - description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible." - default_value: OFF + description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Setting adjusts tracking deadband distance fom waypoint courseline [m]. Tracking isn't actively controlled within the deadband providing smoother flight adjustments but less accurate tracking. A 2m deadband should work OK in most cases. Setting to 0 disables waypoint tracking accuracy." + default_value: 0 field: fw.wp_tracking_accuracy - type: bool + min: 0 + max: 10 - name: nav_fw_wp_tracking_max_angle description: "Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved." default_value: 60 diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 4d8215c688d..e09fbea57a9 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -399,7 +399,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta virtualTargetBearing = calculateBearingToDestination(&virtualDesiredPosition); } - // Calculate cross track error + /* Calculate cross track error */ fpVector3_t virtualCoursePoint; virtualCoursePoint.x = posControl.activeWaypoint.pos.x - posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); @@ -407,8 +407,8 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); - /* If waypoint tracking enabled force craft toward and ckosely track along waypoint course line */ - if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { + /* If waypoint tracking enabled force craft toward and closely track along waypoint course line */ + if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { static float crossTrackErrorRate; static timeUs_t previousCrossTrackErrorUpdateTime; static float previousCrossTrackError = 0.0f; @@ -416,43 +416,28 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(20) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); - if (fabsf(previousCrossTrackError - navCrossTrackError) < 500.0f) { crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec; } crossTrackErrorRate = pt1FilterApply4(&fwCrossTrackErrorRateFilterState, crossTrackErrorRate, 3.0f, crossTrackErrorDtSec); - previousCrossTrackErrorUpdateTime = currentTimeUs; previousCrossTrackError = navCrossTrackError; } - /* Dynamic tracking deadband set at minimum 2m for baseline speed of 60 km/h */ - float trackingDeadband = 200.0f * MAX(posControl.actualState.velXY / 1700.0f, 1.0f); - - /* cutTurnActive improves convergence with course line when WP turn smoothing CUT used */ - static bool cutTurnActive = false; - if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_CUT && posControl.flags.wpTurnSmoothingActive) { - cutTurnActive = true; - } + uint16_t trackingDeadband = METERS_TO_CENTIMETERS(navConfig()->fw.wp_tracking_accuracy); - if (cutTurnActive && !posControl.flags.wpTurnSmoothingActive) { - virtualTargetBearing = wrap_36000(virtualTargetBearing - wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing)); - cutTurnActive = ABS(wrap_18000(posControl.activeWaypoint.bearing - posControl.actualState.cog)) > 500; - } else if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && - navCrossTrackError > trackingDeadband) { + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > trackingDeadband) { float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle); - /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile - * Adjustment limited to navCrossTrackError as course line approached to avoid instability */ + /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */ float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit)); - float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed); - float limit = MIN(angleLimit, navCrossTrackError); - + float desiredApproachSpeed = constrainf(navCrossTrackError, 50.0f, maxApproachSpeed); adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed); - adjustmentFactor = constrainf(adjustmentFactor, -limit, limit); /* Calculate final adjusted virtualTargetBearing */ + uint16_t limit = constrainf(navCrossTrackError, 1000.0f, angleLimit); + adjustmentFactor = constrainf(adjustmentFactor, -limit, limit); virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor); } } From 8c5c91c9b666b370e9c6940aa51b95260e4048f8 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 21 Aug 2024 11:12:16 +0100 Subject: [PATCH 191/212] reinstate fiddle factor --- src/main/navigation/navigation_fixedwing.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index e09fbea57a9..fc8a5a051bc 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -432,7 +432,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */ float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit)); - float desiredApproachSpeed = constrainf(navCrossTrackError, 50.0f, maxApproachSpeed); + float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed); adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed); /* Calculate final adjusted virtualTargetBearing */ From 5d38db02ea77c8eb7af47f8e62c5ebf603501efa Mon Sep 17 00:00:00 2001 From: P-I-Engineer Date: Wed, 21 Aug 2024 06:59:23 -0700 Subject: [PATCH 192/212] Update VTOL.md --- docs/VTOL.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/VTOL.md b/docs/VTOL.md index 64afb333d11..3873eeb4e3f 100644 --- a/docs/VTOL.md +++ b/docs/VTOL.md @@ -186,7 +186,8 @@ Add new servo mixer rules, and select 'Mixer Transition' in input. Set the weigh ## Motor 'Transition Mixing': Dedicated forward motor configuration In motor mixer set: - -2.0 < throttle < -1.0: The motor will spin regardless of the radio's throttle position at a speed of `abs(throttle) - 1` multiplied by throttle range only when Mixer Transition is activated. - +- Airmode type should be set to "STICK_CENTER". Airmode type must NOT be set to "THROTTLE_THRESHOLD". If set to throttle threshold the (-) motor will spin till throttle threshold is passed. + ![Alt text](Screenshots/mixerprofile_4puls1_mix.png) ## TailSitter 'Transition Mixing': @@ -233,4 +234,4 @@ If you set `mixer_automated_switch` to `OFF` for all mixer profiles (the default 2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors. - There will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. ## Dedicated forward motor -- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight \ No newline at end of file +- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight From e0eec2076e8b0a487b0d7c261cceb57dd5f81056 Mon Sep 17 00:00:00 2001 From: P-I-Engineer Date: Wed, 21 Aug 2024 07:01:19 -0700 Subject: [PATCH 193/212] Update MixerProfile.md --- docs/MixerProfile.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index 55aedd3a30b..cd9702b5a32 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -41,6 +41,8 @@ The default `mmix` throttle value is 0.0, It will not show in `diff` command whe - -1.0 Date: Wed, 21 Aug 2024 09:12:55 -0500 Subject: [PATCH 194/212] GEPRC_F722_AIO_UART3 move use i2c --- src/main/target/GEPRC_F722_AIO/target.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h index 3b2ff13f0ac..ee2b9330552 100644 --- a/src/main/target/GEPRC_F722_AIO/target.h +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -56,9 +56,8 @@ #define ICM42605_SPI_BUS BUS_SPI1 // *************** I2C/Baro/Mag ********************* -#define USE_I2C - #ifndef GEPRC_F722_AIO_UART3 +#define USE_I2C #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 #define I2C2_SDA PB11 From 29244a4e8c4d28fd5c14b90bb9fca76fa46e3cbb Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 25 Aug 2024 14:16:44 +0100 Subject: [PATCH 195/212] minor fix --- src/main/navigation/navigation_fixedwing.c | 73 +++++++++++----------- 1 file changed, 37 insertions(+), 36 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index fc8a5a051bc..68232ed7e0b 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -399,49 +399,50 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta virtualTargetBearing = calculateBearingToDestination(&virtualDesiredPosition); } - /* Calculate cross track error */ - fpVector3_t virtualCoursePoint; - virtualCoursePoint.x = posControl.activeWaypoint.pos.x - - posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); - virtualCoursePoint.y = posControl.activeWaypoint.pos.y - - posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); - navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); - - /* If waypoint tracking enabled force craft toward and closely track along waypoint course line */ - if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - static float crossTrackErrorRate; - static timeUs_t previousCrossTrackErrorUpdateTime; - static float previousCrossTrackError = 0.0f; - static pt1Filter_t fwCrossTrackErrorRateFilterState; - - if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(20) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { - const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); - if (fabsf(previousCrossTrackError - navCrossTrackError) < 500.0f) { - crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec; + if (isWaypointNavTrackingActive()) { + /* Calculate cross track error */ + fpVector3_t virtualCoursePoint; + virtualCoursePoint.x = posControl.activeWaypoint.pos.x - + posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + virtualCoursePoint.y = posControl.activeWaypoint.pos.y - + posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); + navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint); + + /* If waypoint tracking enabled force craft toward and closely track along waypoint course line */ + if (navConfig()->fw.wp_tracking_accuracy && !needToCalculateCircularLoiter) { + static float crossTrackErrorRate; + static timeUs_t previousCrossTrackErrorUpdateTime; + static float previousCrossTrackError = 0.0f; + static pt1Filter_t fwCrossTrackErrorRateFilterState; + + if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(20) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) { + const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime); + if (fabsf(previousCrossTrackError - navCrossTrackError) < 500.0f) { + crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec; + } + crossTrackErrorRate = pt1FilterApply4(&fwCrossTrackErrorRateFilterState, crossTrackErrorRate, 3.0f, crossTrackErrorDtSec); + previousCrossTrackErrorUpdateTime = currentTimeUs; + previousCrossTrackError = navCrossTrackError; } - crossTrackErrorRate = pt1FilterApply4(&fwCrossTrackErrorRateFilterState, crossTrackErrorRate, 3.0f, crossTrackErrorDtSec); - previousCrossTrackErrorUpdateTime = currentTimeUs; - previousCrossTrackError = navCrossTrackError; - } - uint16_t trackingDeadband = METERS_TO_CENTIMETERS(navConfig()->fw.wp_tracking_accuracy); + uint16_t trackingDeadband = METERS_TO_CENTIMETERS(navConfig()->fw.wp_tracking_accuracy); - if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > trackingDeadband) { - float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); - uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle); + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > trackingDeadband) { + float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing); + uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle); - /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */ - float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit)); - float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed); - adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed); + /* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */ + float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit)); + float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed); + adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed); - /* Calculate final adjusted virtualTargetBearing */ - uint16_t limit = constrainf(navCrossTrackError, 1000.0f, angleLimit); - adjustmentFactor = constrainf(adjustmentFactor, -limit, limit); - virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor); + /* Calculate final adjusted virtualTargetBearing */ + uint16_t limit = constrainf(navCrossTrackError, 1000.0f, angleLimit); + adjustmentFactor = constrainf(adjustmentFactor, -limit, limit); + virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor); + } } } - /* * Calculate NAV heading error * Units are centidegrees From b5da18fe86fb392fc3001420a301a07aaae68f93 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Mon, 2 Sep 2024 12:41:11 +0200 Subject: [PATCH 196/212] at32: add uart pinswap --- src/main/drivers/serial_uart.h | 4 +- src/main/drivers/serial_uart_at32f43x.c | 81 +++++++++++++++++++-- src/main/drivers/serial_uart_hal_at32f43x.c | 1 + src/main/target/NEUTRONRCF435MINI/target.h | 5 +- 4 files changed, 80 insertions(+), 11 deletions(-) diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index b8e72026128..4c1e6d57508 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -50,7 +50,8 @@ typedef enum { UARTDEV_5 = 4, UARTDEV_6 = 5, UARTDEV_7 = 6, - UARTDEV_8 = 7 + UARTDEV_8 = 7, + UARTDEV_MAX } UARTDevice_e; typedef struct { @@ -69,6 +70,7 @@ typedef struct { void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins); void uartClearIdleFlag(uartPort_t *s); +void uartConfigurePinSwap(uartPort_t *uartPort); #if defined(AT32F43x) serialPort_t *uartOpen(usart_type *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); #else diff --git a/src/main/drivers/serial_uart_at32f43x.c b/src/main/drivers/serial_uart_at32f43x.c index 354ea6c9343..90ebe05ef82 100644 --- a/src/main/drivers/serial_uart_at32f43x.c +++ b/src/main/drivers/serial_uart_at32f43x.c @@ -45,6 +45,7 @@ typedef struct uartDevice_s { uint8_t af; uint8_t irq; uint32_t irqPriority; + bool pinSwap; } uartDevice_t; #ifdef USE_UART1 @@ -59,7 +60,12 @@ static uartDevice_t uart1 = #endif .rcc_apb2 = RCC_APB2(USART1), .irq = USART1_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART1_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -75,7 +81,12 @@ static uartDevice_t uart2 = #endif .rcc_apb1 = RCC_APB1(USART2), .irq = USART2_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART2_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -91,7 +102,12 @@ static uartDevice_t uart3 = #endif .rcc_apb1 = RCC_APB1(USART3), .irq = USART3_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART3_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -107,7 +123,12 @@ static uartDevice_t uart4 = #endif .rcc_apb1 = RCC_APB1(UART4), .irq = UART4_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART4_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -123,7 +144,12 @@ static uartDevice_t uart5 = #endif .rcc_apb1 = RCC_APB1(UART5), .irq = UART5_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART5_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -139,7 +165,12 @@ static uartDevice_t uart6 = #endif .rcc_apb2 = RCC_APB2(USART6), .irq = USART6_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART6_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -152,7 +183,12 @@ static uartDevice_t uart7 = .af = GPIO_MUX_8, .rcc_apb1 = RCC_APB1(UART7), .irq = UART7_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART7_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -165,7 +201,12 @@ static uartDevice_t uart8 = .af = GPIO_MUX_8, .rcc_apb1 = RCC_APB1(UART8), .irq = UART8_IRQn, - .irqPriority = NVIC_PRIO_SERIALUART + .irqPriority = NVIC_PRIO_SERIALUART, +#ifdef USE_UART8_PIN_SWAP + .pinSwap = true, +#else + .pinSwap = false, +#endif }; #endif @@ -258,6 +299,30 @@ void uartClearIdleFlag(uartPort_t *s) (void) s->USARTx->dt; } +static uartDevice_t *uartFindDevice(uartPort_t *uartPort) +{ + for (uint32_t i = 0; i < UARTDEV_MAX; i++) { + uartDevice_t *pDevice = uartHardwareMap[i]; + + if (pDevice->dev == uartPort->USARTx) { + return pDevice; + } + } + return NULL; +} + +void uartConfigurePinSwap(uartPort_t *uartPort) +{ + uartDevice_t *uartDevice = uartFindDevice(uartPort); + if (!uartDevice) { + return; + } + + if (uartDevice->pinSwap) { + usart_transmit_receive_pin_swap(uartPort->USARTx, TRUE); + } +} + uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; diff --git a/src/main/drivers/serial_uart_hal_at32f43x.c b/src/main/drivers/serial_uart_hal_at32f43x.c index a06869ba10c..f30726332f4 100644 --- a/src/main/drivers/serial_uart_hal_at32f43x.c +++ b/src/main/drivers/serial_uart_hal_at32f43x.c @@ -85,6 +85,7 @@ static void uartReconfigure(uartPort_t *uartPort) usart_transmitter_enable(uartPort->USARTx, TRUE); usartConfigurePinInversion(uartPort); + uartConfigurePinSwap(uartPort); if (uartPort->port.options & SERIAL_BIDIR) usart_single_line_halfduplex_select(uartPort->USARTx, TRUE); diff --git a/src/main/target/NEUTRONRCF435MINI/target.h b/src/main/target/NEUTRONRCF435MINI/target.h index 2e90f48a69d..6ef53abf64d 100644 --- a/src/main/target/NEUTRONRCF435MINI/target.h +++ b/src/main/target/NEUTRONRCF435MINI/target.h @@ -144,8 +144,9 @@ #define UART2_TX_PIN PA2 #define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define USE_UART3_PIN_SWAP +#define UART3_RX_PIN PB10 +#define UART3_TX_PIN PB11 #define USE_UART5 #define UART5_RX_PIN PB8 From 570b301d440a59c15bcc7306303963d62b4e7b17 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 2 Sep 2024 21:16:48 +0100 Subject: [PATCH 197/212] Align update rate for WP distance with XT error --- src/main/navigation/navigation_fixedwing.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 68232ed7e0b..ff38b2e17e5 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -401,6 +401,8 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta if (isWaypointNavTrackingActive()) { /* Calculate cross track error */ + posControl.wpDistance = calculateDistanceToDestination(&posControl.activeWaypoint.pos); + fpVector3_t virtualCoursePoint; virtualCoursePoint.x = posControl.activeWaypoint.pos.x - posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing)); From 3f9f70f8e8e1da0f2912e5acc7a9d06487557f48 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Mon, 2 Sep 2024 11:17:35 +0200 Subject: [PATCH 198/212] lucid: remove in-accessible servo pins --- src/main/target/TBS_LUCID_FC/target.c | 10 ++-------- src/main/target/TBS_LUCID_FC/target.h | 2 +- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/src/main/target/TBS_LUCID_FC/target.c b/src/main/target/TBS_LUCID_FC/target.c index 213948bacce..e6c7a3830ab 100644 --- a/src/main/target/TBS_LUCID_FC/target.c +++ b/src/main/target/TBS_LUCID_FC/target.c @@ -37,16 +37,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 3), // S3 DEF_TIM(TMR3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 4), // S4 - DEF_TIM(TMR2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 8), // S5 - DEF_TIM(TMR2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 9), // S6 - DEF_TIM(TMR2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 10), // S7 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 11), // S8 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 8), // S5 + DEF_TIM(TMR4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 9), // S6 DEF_TIM(TMR1, CH1, PA8, TIM_USE_LED, 0, 5), // LED Strip - - DEF_TIM(TMR4, CH2, PB7, TIM_USE_ANY, 0, 6), // Aux - DEF_TIM(TMR4, CH3, PB8, TIM_USE_ANY, 0, 7), // Aux - }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TBS_LUCID_FC/target.h b/src/main/target/TBS_LUCID_FC/target.h index b608622d1ed..7a9ed60fb52 100644 --- a/src/main/target/TBS_LUCID_FC/target.h +++ b/src/main/target/TBS_LUCID_FC/target.h @@ -140,7 +140,7 @@ #define USE_ESC_SENSOR #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define MAX_PWM_OUTPUT_PORTS 10 +#define MAX_PWM_OUTPUT_PORTS 6 #define DEFAULT_FEATURES \ (FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_OSD | \ From a2187ce16616bf21359202fe6f52921aa6d76d60 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 3 Sep 2024 12:37:33 +0100 Subject: [PATCH 199/212] change WP mode linear climb method --- src/main/navigation/navigation.c | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e43eb9d8534..4ae4cf228db 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1859,6 +1859,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav case NAV_WP_ACTION_LAND: calculateAndSetActiveWaypoint(&posControl.waypointList[posControl.activeWaypointIndex]); posControl.wpInitialDistance = calculateDistanceToDestination(&posControl.activeWaypoint.pos); + posControl.wpInitialAltitude = posControl.actualState.abs.pos.z; posControl.wpAltitudeReached = false; return NAV_FSM_EVENT_SUCCESS; // will switch to NAV_STATE_WAYPOINT_IN_PROGRESS @@ -1922,16 +1923,12 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na fpVector3_t tmpWaypoint; tmpWaypoint.x = posControl.activeWaypoint.pos.x; tmpWaypoint.y = posControl.activeWaypoint.pos.y; - setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_BEARING); - - // Use linear climb between WPs arriving at WP altitude when within 10% of total distance to WP - // Update climb rate until within 100cm of total climb xy distance to WP - float climbRate = 0.0f; - if (posControl.wpDistance - 0.1f * posControl.wpInitialDistance > 100.0f) { - climbRate = posControl.actualState.velXY * (posControl.activeWaypoint.pos.z - posControl.actualState.abs.pos.z) / - (posControl.wpDistance - 0.1f * posControl.wpInitialDistance); - } - updateClimbRateToAltitudeController(climbRate, posControl.activeWaypoint.pos.z, ROC_TO_ALT_TARGET); + /* Use linear climb/descent between WPs arriving at WP altitude when within 10% of total distance to WP */ + tmpWaypoint.z = scaleRangef(constrainf(posControl.wpDistance, 0.1f * posControl.wpInitialDistance, posControl.wpInitialDistance), + posControl.wpInitialDistance, 0.1f * posControl.wpInitialDistance, + posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z); + + setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING); if(STATE(MULTIROTOR)) { switch (wpHeadingControl.mode) { @@ -3703,7 +3700,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) setDesiredPosition(&wpPos.pos, DEGREES_TO_CENTIDEGREES(wpData->p1), waypointUpdateFlags); } // WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission - else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !FLIGHT_MODE(NAV_WP_MODE)) { + else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !FLIGHT_MODE(NAV_WP_MODE)) { // WP upload is not allowed why WP mode is active if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) From a0c1717670757b4da10412fccd2eaf323c70972a Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Sep 2024 18:16:08 +0200 Subject: [PATCH 200/212] Update ci.yml --- .github/workflows/ci.yml | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 4663febe50e..76b85db3ba0 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -40,12 +40,13 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - uses: actions/cache@v4 with: path: downloads key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}} - name: Build targets (${{ matrix.id }}) - run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j4 ci + run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci - name: Upload artifacts uses: actions/upload-artifact@v4 with: @@ -74,6 +75,7 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - name: Download artifacts uses: actions/download-artifact@v4 with: @@ -116,8 +118,9 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - name: Build SITL - run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j4 + run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j${{ env.NUM_CORES }} - name: Upload artifacts uses: actions/upload-artifact@v4 with: @@ -148,11 +151,12 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - name: Build SITL run: | mkdir -p build_SITL && cd build_SITL cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -G Ninja .. - ninja -j3 + ninja -j4 - name: Upload artifacts uses: actions/upload-artifact@v4 @@ -187,6 +191,7 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + - name: Build SITL run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j4 - name: Upload artifacts From 8c19013b81fcfb8aaae13bc865585a54fceb8a1b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Sep 2024 18:35:28 +0200 Subject: [PATCH 201/212] Update dev-builds.yml --- .github/workflows/dev-builds.yml | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/.github/workflows/dev-builds.yml b/.github/workflows/dev-builds.yml index 94492966f79..c107e24521d 100644 --- a/.github/workflows/dev-builds.yml +++ b/.github/workflows/dev-builds.yml @@ -42,12 +42,13 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - uses: actions/cache@v4 with: path: downloads key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}} - name: Build targets (${{ matrix.id }}) - run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DVERSION_TYPE=dev -G Ninja .. && ninja ci + run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -DVERSION_TYPE=dev -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci - name: Upload artifacts uses: actions/upload-artifact@v4 with: @@ -76,8 +77,9 @@ jobs: VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }') echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV + echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV - name: Build SITL - run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja -DVERSION_TYPE=dev .. && ninja + run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja -DVERSION_TYPE=dev .. && ninja -j${{ env.NUM_CORES }} - name: Upload artifacts uses: actions/upload-artifact@v4 with: @@ -112,7 +114,7 @@ jobs: run: | mkdir -p build_SITL && cd build_SITL cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -DVERSION_TYPE=dev -G Ninja .. - ninja + ninja -j4 - name: Upload artifacts uses: actions/upload-artifact@v4 @@ -150,7 +152,7 @@ jobs: #echo "VERSION_TAG=-$(date '+%Y%m%d')" >> $GITHUB_ENV echo "version=${VERSION}" >> $GITHUB_OUTPUT - name: Build SITL - run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DVERSION_TYPE=dev -G Ninja .. && ninja + run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DVERSION_TYPE=dev -G Ninja .. && ninja -j4 - name: Upload artifacts uses: actions/upload-artifact@v4 with: From dd82cd86ef65f5f06016e35718a15f2a8721d2fb Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Sep 2024 15:47:35 +0200 Subject: [PATCH 202/212] iFlight IFLIGHT_BLITZ_H7_WING changes --- src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt | 3 ++- src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h | 11 ++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt b/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt index b8fc79235d4..c4bd2c43840 100644 --- a/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt +++ b/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt @@ -1 +1,2 @@ -target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO) \ No newline at end of file +target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO) +target_stm32h743xi(IFLIGHT_BLITZ_H7_WING) \ No newline at end of file diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h index 23fde63466c..7d93ec91ce6 100644 --- a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h +++ b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h @@ -20,7 +20,11 @@ #define TARGET_BOARD_IDENTIFIER "IB7P" +#ifdef IFLIGHT_BLITZ_H7_PRO #define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_PRO" +#else +#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_WING" +#endif #define USE_TARGET_CONFIG @@ -161,7 +165,12 @@ #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define CURRENT_METER_SCALE 212 -#define VBAT_SCALE_DEFAULT 1135 + +#ifdef IFLIGHT_BLITZ_H7_PRO +#define VBAT_SCALE_DEFAULT 2100 +#else +#define VBAT_SCALE_DEFAULT 1100 +#endif #define USE_SERIAL_4WAY_BLHELI_INTERFACE From d9596a1ef43e3142504dc33d1aa4e72631c9644f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 5 Sep 2024 18:13:20 +0200 Subject: [PATCH 203/212] Add some debugging for msp headtracker --- src/main/io/headtracker_msp.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/io/headtracker_msp.c b/src/main/io/headtracker_msp.c index 8a800b3f46e..6c03f89130f 100644 --- a/src/main/io/headtracker_msp.c +++ b/src/main/io/headtracker_msp.c @@ -56,6 +56,7 @@ void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize) { if(dataSize != sizeof(headtrackerMspMessage_t)) { SD(fprintf(stderr, "[headTracker]: invalid data size %d\n", dataSize)); + DEBUG_SET(DEBUG_HEADTRACKING, 7, 1); return; } @@ -66,7 +67,10 @@ void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize) headTrackerMspDevice.roll = constrain(status->roll, HEADTRACKER_RANGE_MIN, HEADTRACKER_RANGE_MAX); headTrackerMspDevice.expires = micros() + MAX_HEADTRACKER_DATA_AGE_US; - UNUSED(status); + DEBUG_SET(DEBUG_HEADTRACKING, 0, headTrackerMspDevice.pan); + DEBUG_SET(DEBUG_HEADTRACKING, 1, headTrackerMspDevice.tilt); + DEBUG_SET(DEBUG_HEADTRACKING, 2, headTrackerMspDevice.roll); + DEBUG_SET(DEBUG_HEADTRACKING, 3, headTrackerMspDevice.expires); } headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *headTrackerDevice) { From db9723e4bed9c5c36ee52b0756cc15c41e1faa0c Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 5 Sep 2024 19:19:59 +0200 Subject: [PATCH 204/212] More permissive parsing. --- src/main/fc/fc_msp.c | 2 +- src/main/io/headtracker_msp.c | 7 +++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index e7a7a4aa3a6..2b544ee449a 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4127,7 +4127,7 @@ static mspResult_e mspProcessSensorCommand(uint16_t cmdMSP, sbuf_t *src) #if (defined(USE_HEADTRACKER) && defined(USE_HEADTRACKER_MSP)) case MSP2_SENSOR_HEADTRACKER: - mspHeadTrackerReceiverNewData(sbufPtr(src), dataSize); + mspHeadTrackerReceiverNewData(sbufPtr(src), sbufBytesRemaining(src)); break; #endif } diff --git a/src/main/io/headtracker_msp.c b/src/main/io/headtracker_msp.c index 6c03f89130f..b90064caa81 100644 --- a/src/main/io/headtracker_msp.c +++ b/src/main/io/headtracker_msp.c @@ -54,9 +54,12 @@ void mspHeadTrackerInit(void) void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize) { - if(dataSize != sizeof(headtrackerMspMessage_t)) { + if(dataSize >= sizeof(headtrackerMspMessage_t)) { SD(fprintf(stderr, "[headTracker]: invalid data size %d\n", dataSize)); - DEBUG_SET(DEBUG_HEADTRACKING, 7, 1); + static int errorCount = 0; + DEBUG_SET(DEBUG_HEADTRACKING, 7, errorCount++); + DEBUG_SET(DEBUG_HEADTRACKING, 5, (sizeof(headtrackerMspMessage_t))); + DEBUG_SET(DEBUG_HEADTRACKING, 6, dataSize); return; } From 9dcdb543f48822142f8437ab62df74aac4af412f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 5 Sep 2024 19:25:36 +0200 Subject: [PATCH 205/212] Warning fix --- src/main/io/headtracker_msp.c | 2 +- src/main/io/headtracker_msp.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/headtracker_msp.c b/src/main/io/headtracker_msp.c index b90064caa81..24c409469ed 100644 --- a/src/main/io/headtracker_msp.c +++ b/src/main/io/headtracker_msp.c @@ -52,7 +52,7 @@ void mspHeadTrackerInit(void) } } -void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize) +void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize) { if(dataSize >= sizeof(headtrackerMspMessage_t)) { SD(fprintf(stderr, "[headTracker]: invalid data size %d\n", dataSize)); diff --git a/src/main/io/headtracker_msp.h b/src/main/io/headtracker_msp.h index edcfb465874..f767b1c6286 100644 --- a/src/main/io/headtracker_msp.h +++ b/src/main/io/headtracker_msp.h @@ -37,7 +37,7 @@ typedef struct headtrackerMspMessage_s { void mspHeadTrackerInit(void); -void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize); +void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize); headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *headTrackerDevice); From 9849d69ee28889b20216709e06b0c676e89140a5 Mon Sep 17 00:00:00 2001 From: Sensei Date: Fri, 6 Sep 2024 01:31:32 -0500 Subject: [PATCH 206/212] Update USB Flashing.md - mention using a hub with USB-C --- docs/USB Flashing.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index 9d79d5cd8d1..ade5ae2ba4a 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -60,7 +60,7 @@ With the board connected and in bootloader mode (reset it by sending the charact * If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle. * A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts. - * Using a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works. + * Using either a hub woth USB-A ports, or a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works. ## Using `dfu-util` From 842cbfb5da6ec76af132b36cf3a46860c581f209 Mon Sep 17 00:00:00 2001 From: Sensei Date: Fri, 6 Sep 2024 01:33:05 -0500 Subject: [PATCH 207/212] Update USB Flashing.md - typo --- docs/USB Flashing.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index ade5ae2ba4a..97787c7fb48 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -60,7 +60,7 @@ With the board connected and in bootloader mode (reset it by sending the charact * If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle. * A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts. - * Using either a hub woth USB-A ports, or a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works. + * Using either a hub with USB-A ports, or a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works. ## Using `dfu-util` From 73f4ace3a2c5f15159b6146a9833615f0f016a09 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 6 Sep 2024 11:58:19 +0200 Subject: [PATCH 208/212] Update ci.yml --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 4663febe50e..28873b19fff 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -18,7 +18,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16] + id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] steps: - uses: actions/checkout@v4 From a3c503fb4c8a2cfd006df9102e9e1537da497fef Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 6 Sep 2024 12:05:23 +0200 Subject: [PATCH 209/212] Update dev-builds.yml --- .github/workflows/dev-builds.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/dev-builds.yml b/.github/workflows/dev-builds.yml index 94492966f79..c633ec827b8 100644 --- a/.github/workflows/dev-builds.yml +++ b/.github/workflows/dev-builds.yml @@ -20,7 +20,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16] + id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15] steps: - uses: actions/checkout@v4 From 3ef2c56c2e2b23c14a6593d1f6ec045e19ac9de5 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 7 Sep 2024 00:00:58 +0200 Subject: [PATCH 210/212] Small fixes for serial gimbal --- src/main/fc/fc_msp.c | 2 +- src/main/io/gimbal_serial.c | 6 ++++-- src/main/io/headtracker_msp.c | 17 +++++++++++++++-- src/main/io/headtracker_msp.h | 1 + 4 files changed, 21 insertions(+), 5 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 2b544ee449a..e7a7a4aa3a6 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4127,7 +4127,7 @@ static mspResult_e mspProcessSensorCommand(uint16_t cmdMSP, sbuf_t *src) #if (defined(USE_HEADTRACKER) && defined(USE_HEADTRACKER_MSP)) case MSP2_SENSOR_HEADTRACKER: - mspHeadTrackerReceiverNewData(sbufPtr(src), sbufBytesRemaining(src)); + mspHeadTrackerReceiverNewData(sbufPtr(src), dataSize); break; #endif } diff --git a/src/main/io/gimbal_serial.c b/src/main/io/gimbal_serial.c index 4eec2903947..085590f0880 100644 --- a/src/main/io/gimbal_serial.c +++ b/src/main/io/gimbal_serial.c @@ -116,7 +116,9 @@ bool gimbalSerialIsReady(const gimbalDevice_t *gimbalDevice) bool gimbalSerialHasHeadTracker(const gimbalDevice_t *gimbalDevice) { UNUSED(gimbalDevice); - return headTrackerPort || (gimbalSerialConfig()->singleUart && gimbalPort); + + headTrackerDevice_t *htrk = headTrackerCommonDevice(); + return htrk != NULL && headTrackerCommonIsReady(htrk); } bool gimbalSerialInit(void) @@ -251,7 +253,7 @@ void gimbalSerialProcess(gimbalDevice_t *gimbalDevice, timeUs_t currentTime) #else { #endif - DEBUG_SET(DEBUG_HEADTRACKING, 4, 0); + DEBUG_SET(DEBUG_HEADTRACKING, 4, 2); // Radio endpoints may need to be adjusted, as it seems ot go a bit // bananas at the extremes attitude.pan = gimbal_scale12(PWM_RANGE_MIN, PWM_RANGE_MAX, panPWM); diff --git a/src/main/io/headtracker_msp.c b/src/main/io/headtracker_msp.c index 24c409469ed..ad2a8842f7c 100644 --- a/src/main/io/headtracker_msp.c +++ b/src/main/io/headtracker_msp.c @@ -30,10 +30,11 @@ #include "io/headtracker_msp.h" +static bool isReady = false; static headTrackerVTable_t headTrackerMspVTable = { .process = NULL, .getDeviceType = heatTrackerMspGetDeviceType, - .isReady = NULL, + .isReady = heatTrackerMspIsReady, .isValid = NULL, }; @@ -47,6 +48,9 @@ static headTrackerDevice_t headTrackerMspDevice = { void mspHeadTrackerInit(void) { + for(int i = 0; i < 8;++i) { + DEBUG_SET(DEBUG_HEADTRACKING, i, 0); + } if(headTrackerConfig()->devType == HEADTRACKER_MSP) { headTrackerCommonSetDevice(&headTrackerMspDevice); } @@ -54,7 +58,7 @@ void mspHeadTrackerInit(void) void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize) { - if(dataSize >= sizeof(headtrackerMspMessage_t)) { + if(dataSize != sizeof(headtrackerMspMessage_t)) { SD(fprintf(stderr, "[headTracker]: invalid data size %d\n", dataSize)); static int errorCount = 0; DEBUG_SET(DEBUG_HEADTRACKING, 7, errorCount++); @@ -62,6 +66,8 @@ void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize) DEBUG_SET(DEBUG_HEADTRACKING, 6, dataSize); return; } + isReady = true; + DEBUG_SET(DEBUG_HEADTRACKING, 6, dataSize); headtrackerMspMessage_t *status = (headtrackerMspMessage_t *)data; @@ -81,4 +87,11 @@ headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *head return HEADTRACKER_MSP; } + +bool heatTrackerMspIsReady(const headTrackerDevice_t *headTrackerDevice) +{ + UNUSED(headTrackerDevice); + return headTrackerConfig()->devType == HEADTRACKER_MSP && isReady; +} + #endif \ No newline at end of file diff --git a/src/main/io/headtracker_msp.h b/src/main/io/headtracker_msp.h index f767b1c6286..e082d0db8ae 100644 --- a/src/main/io/headtracker_msp.h +++ b/src/main/io/headtracker_msp.h @@ -40,5 +40,6 @@ void mspHeadTrackerInit(void); void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize); headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *headTrackerDevice); +bool heatTrackerMspIsReady(const headTrackerDevice_t *headTrackerDevice); #endif From 2ac360336c8d4bd01c5dbe1a46810ac78dfba8b7 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 7 Sep 2024 00:03:06 +0200 Subject: [PATCH 211/212] Update headtracker_msp.c --- src/main/io/headtracker_msp.c | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/io/headtracker_msp.c b/src/main/io/headtracker_msp.c index ad2a8842f7c..e53fd3ab207 100644 --- a/src/main/io/headtracker_msp.c +++ b/src/main/io/headtracker_msp.c @@ -48,9 +48,6 @@ static headTrackerDevice_t headTrackerMspDevice = { void mspHeadTrackerInit(void) { - for(int i = 0; i < 8;++i) { - DEBUG_SET(DEBUG_HEADTRACKING, i, 0); - } if(headTrackerConfig()->devType == HEADTRACKER_MSP) { headTrackerCommonSetDevice(&headTrackerMspDevice); } @@ -94,4 +91,4 @@ bool heatTrackerMspIsReady(const headTrackerDevice_t *headTrackerDevice) return headTrackerConfig()->devType == HEADTRACKER_MSP && isReady; } -#endif \ No newline at end of file +#endif From 2511cc31cb0edfa8bb229e11c911e2180c35af3e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 7 Sep 2024 00:15:58 +0200 Subject: [PATCH 212/212] Unit test fixes --- src/main/drivers/headtracker_common.c | 4 ---- src/main/drivers/headtracker_common.h | 3 ++- src/main/drivers/time.h | 7 +++++++ src/main/io/gimbal_serial.c | 2 +- src/test/unit/CMakeLists.txt | 4 ++-- src/test/unit/gimbal_serial_unittest.cc | 6 ++++++ 6 files changed, 18 insertions(+), 8 deletions(-) diff --git a/src/main/drivers/headtracker_common.c b/src/main/drivers/headtracker_common.c index feec581da8a..8ea71cd2f66 100644 --- a/src/main/drivers/headtracker_common.c +++ b/src/main/drivers/headtracker_common.c @@ -157,10 +157,6 @@ void taskUpdateHeadTracker(timeUs_t currentTimeUs) #else void taskUpdateHeadTracker(timeUs_t currentTimeUs) { - if (cliMode) { - return; - } - headTrackerDevice_t *headTrackerDevice = headTrackerCommonDevice(); if(headTrackerDevice) { diff --git a/src/main/drivers/headtracker_common.h b/src/main/drivers/headtracker_common.h index 8c177e3e0f0..92dac7e61e6 100644 --- a/src/main/drivers/headtracker_common.h +++ b/src/main/drivers/headtracker_common.h @@ -23,7 +23,6 @@ #define HEADTRACKER_RANGE_MIN -2048 #define HEADTRACKER_RANGE_MAX 2047 -#ifdef USE_HEADTRACKER #include @@ -81,6 +80,8 @@ typedef struct headTrackerConfig_s { float roll_ratio; } headTrackerConfig_t; +#ifdef USE_HEADTRACKER + PG_DECLARE(headTrackerConfig_t, headTrackerConfig); void headTrackerCommonInit(void); diff --git a/src/main/drivers/time.h b/src/main/drivers/time.h index 6901d57c19b..ea30592515e 100644 --- a/src/main/drivers/time.h +++ b/src/main/drivers/time.h @@ -19,6 +19,9 @@ #include +#ifdef __cplusplus +extern "C" { +#endif #include "common/time.h" extern uint32_t usTicks; @@ -32,3 +35,7 @@ timeUs_t microsISR(void); timeMs_t millis(void); uint32_t ticks(void); + +#ifdef __cplusplus +} +#endif \ No newline at end of file diff --git a/src/main/io/gimbal_serial.c b/src/main/io/gimbal_serial.c index 085590f0880..fd6294c9959 100644 --- a/src/main/io/gimbal_serial.c +++ b/src/main/io/gimbal_serial.c @@ -63,11 +63,11 @@ static gimbalSerialHtrkState_t headTrackerState = { .attitude = {}, .state = WAITING_HDR1, }; +static serialPort_t *headTrackerPort = NULL; #endif #endif -static serialPort_t *headTrackerPort = NULL; static serialPort_t *gimbalPort = NULL; gimbalVTable_t gimbalSerialVTable = { diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index 300721b8f53..2cb53b64ecb 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -40,8 +40,8 @@ set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST USE_MSP_D set_property(SOURCE gps_ublox_unittest.cc PROPERTY depends "io/gps_ublox_utils.c") set_property(SOURCE gps_ublox_unittest.cc PROPERTY definitions GPS_UBLOX_UNIT_TEST) -set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial.c" "drivers/gimbal_common.c" "common/maths.c") -set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST) +set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial.c" "drivers/gimbal_common.c" "common/maths.c" "drivers/headtracker_common.c") +set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER) function(unit_test src) get_filename_component(basename ${src} NAME) diff --git a/src/test/unit/gimbal_serial_unittest.cc b/src/test/unit/gimbal_serial_unittest.cc index 1f0c47231c6..4ca55e17ee2 100644 --- a/src/test/unit/gimbal_serial_unittest.cc +++ b/src/test/unit/gimbal_serial_unittest.cc @@ -34,6 +34,12 @@ void dumpMemory(uint8_t *mem, int size) printf("\n"); } +extern "C" { +timeUs_t micros(void) { + return 10; +} +} + TEST(GimbalSerialTest, TestGimbalSerialScale) { int16_t res16 = gimbal_scale12(1000, 2000, 2000);